Browse Source

Use MAV_CMD_DO_SET_MODE to change modes on ArduPilot-base vehicles

ArduPilot has supported this command for 5.5 years now.  Probably time to start using it.  Copter 3.6.0 has it, 3.5.x does not.
QGC4.4
Peter Barker 2 years ago committed by Patrick José Pereira
parent
commit
231f300e7f
  1. 1
      src/FirmwarePlugin/APM/APMFirmwarePlugin.h
  2. 3
      src/FirmwarePlugin/FirmwarePlugin.h
  3. 26
      src/Vehicle/Vehicle.cc

1
src/FirmwarePlugin/APM/APMFirmwarePlugin.h

@ -56,6 +56,7 @@ public:
QStringList flightModes (Vehicle* vehicle) override; QStringList flightModes (Vehicle* vehicle) override;
QString flightMode (uint8_t base_mode, uint32_t custom_mode) const override; QString flightMode (uint8_t base_mode, uint32_t custom_mode) const override;
bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) override; bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) override;
bool MAV_CMD_DO_SET_MODE_is_supported() const override { return true; }
bool isGuidedMode (const Vehicle* vehicle) const override; bool isGuidedMode (const Vehicle* vehicle) const override;
QString gotoFlightMode (void) const override { return QStringLiteral("Guided"); } QString gotoFlightMode (void) const override { return QStringLiteral("Guided"); }
QString rtlFlightMode (void) const override { return QString("RTL"); } QString rtlFlightMode (void) const override { return QString("RTL"); }

3
src/FirmwarePlugin/FirmwarePlugin.h

@ -102,6 +102,9 @@ public:
/// @param[out] custom_mode Custom mode for SET_MODE mavlink message /// @param[out] custom_mode Custom mode for SET_MODE mavlink message
virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode); virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
/// returns true if this flight stack supports MAV_CMD_DO_SET_MODE
virtual bool MAV_CMD_DO_SET_MODE_is_supported() const { return false; }
/// Returns The flight mode which indicates the vehicle is paused /// Returns The flight mode which indicates the vehicle is paused
virtual QString pauseFlightMode(void) const { return QString(); } virtual QString pauseFlightMode(void) const { return QString(); }

26
src/Vehicle/Vehicle.cc

@ -2202,15 +2202,23 @@ void Vehicle::setFlightMode(const QString& flightMode)
// states. // states.
newBaseMode |= base_mode; newBaseMode |= base_mode;
mavlink_message_t msg; if (_firmwarePlugin->MAV_CMD_DO_SET_MODE_is_supported()) {
mavlink_msg_set_mode_pack_chan(_mavlink->getSystemId(), sendMavCommand(defaultComponentId(),
_mavlink->getComponentId(), MAV_CMD_DO_SET_MODE,
sharedLink->mavlinkChannel(), true, // show error if fails
&msg, MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
id(), custom_mode);
newBaseMode, } else {
custom_mode); mavlink_message_t msg;
sendMessageOnLinkThreadSafe(sharedLink.get(), msg); mavlink_msg_set_mode_pack_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
sharedLink->mavlinkChannel(),
&msg,
id(),
newBaseMode,
custom_mode);
sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
}
} else { } else {
qCWarning(VehicleLog) << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode; qCWarning(VehicleLog) << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode;
} }

Loading…
Cancel
Save