GCS_MAVLink: Use the vehicle singleton to directly set the flight mode

This commit is contained in:
Michael du Breuil 2019-10-16 20:47:39 -07:00 committed by Randy Mackay
parent a44a7f541b
commit cb1b236439
3 changed files with 1 additions and 3 deletions

View File

@ -285,7 +285,6 @@ protected:
// overridable method to check for packet acceptance. Allows for
// enforcement of GCS sysid
bool accept_packet(const mavlink_status_t &status, const mavlink_message_t &msg);
virtual bool set_mode(uint8_t mode) = 0;
void set_ekf_origin(const Location& loc);
virtual MAV_MODE base_mode() const = 0;

View File

@ -2013,7 +2013,7 @@ MAV_RESULT GCS_MAVLINK::_set_mode_common(const MAV_MODE _base_mode, const uint32
MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
// only accept custom modes because there is no easy mapping from Mavlink flight modes to AC flight modes
if (_base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
if (set_mode(_custom_mode)) {
if (AP::vehicle()->set_mode(_custom_mode, ModeReason::GCS_COMMAND)) {
result = MAV_RESULT_ACCEPTED;
}
} else if (_base_mode == (MAV_MODE)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {

View File

@ -38,7 +38,6 @@ private:
protected:
uint8_t sysid_my_gcs() const override { return 1; }
bool set_mode(uint8_t mode) override { return false; };
// dummy information:
MAV_MODE base_mode() const override { return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }