public void setMode(string modein) { try { MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t(); if (translateMode(modein, ref mode)) { setMode(mode); } } catch { System.Windows.Forms.MessageBox.Show("Failed to change Modes"); } }
public void setMode(string modein) { #if MAVLINK10 try { MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t(); if (translateMode(modein, ref mode)) { setMode(mode); } } catch { System.Windows.Forms.MessageBox.Show("Failed to change Modes"); } #else try { MAVLink.mavlink_set_nav_mode_t navmode = new MAVLink.mavlink_set_nav_mode_t(); MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t(); if (translateMode(modein, ref navmode, ref mode)) { generatePacket((byte)MAVLink.MAVLINK_MSG_ID_SET_NAV_MODE, navmode); System.Threading.Thread.Sleep(10); generatePacket((byte)MAVLink.MAVLINK_MSG_ID_SET_MODE, mode); System.Threading.Thread.Sleep(10); generatePacket((byte)MAVLink.MAVLINK_MSG_ID_SET_NAV_MODE, navmode); System.Threading.Thread.Sleep(10); generatePacket((byte)MAVLink.MAVLINK_MSG_ID_SET_MODE, mode); } } catch { System.Windows.Forms.CustomMessageBox.Show("Failed to change Modes"); } #endif }