Sub: use GCS_MAVLINK subclasses to handle set_mode

This commit is contained in:
Peter Barker 2017-08-11 16:18:45 +10:00 committed by Francisco Ferreira
parent 947bae2f86
commit 5a9af5bc28
3 changed files with 7 additions and 8 deletions

View File

@ -830,11 +830,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
break;
}
case MAVLINK_MSG_ID_SET_MODE: { // MAV ID: 11
handle_set_mode(msg, FUNCTOR_BIND(&sub, &Sub::gcs_set_mode, bool, uint8_t));
break;
}
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { // MAV ID: 21
// mark the firmware version in the tlog
send_text(MAV_SEVERITY_INFO, FIRMWARE_STRING);
@ -1610,5 +1605,10 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_long
return MAV_RESULT_FAILED;
}
bool GCS_MAVLINK_Sub::set_mode(uint8_t mode)
{
return sub.set_mode((control_mode_t)mode, MODE_REASON_GCS_COMMAND);
}
// dummy method to avoid linking AFS
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate) { return false; }

View File

@ -24,6 +24,8 @@ protected:
uint8_t sysid_my_gcs() const override;
bool set_mode(uint8_t mode) override;
private:
void handleMessage(mavlink_message_t * msg) override;

View File

@ -599,9 +599,6 @@ private:
void fence_check();
void fence_send_mavlink_status(mavlink_channel_t chan);
bool set_mode(control_mode_t mode, mode_reason_t reason);
bool gcs_set_mode(uint8_t mode) {
return set_mode((control_mode_t)mode, MODE_REASON_GCS_COMMAND);
}
void update_flight_mode();
void exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode);
bool mode_requires_GPS(control_mode_t mode);