Copter: move send_autopilot_request calls up to GCS base class

This commit is contained in:
Peter Barker 2017-08-19 08:46:48 +10:00 committed by Francisco Ferreira
parent add1743c12
commit bb06db6389
2 changed files with 6 additions and 12 deletions

View File

@ -1149,14 +1149,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
break;
#endif
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: {
if (is_equal(packet.param1,1.0f)) {
send_autopilot_version(FIRMWARE_VERSION);
result = MAV_RESULT_ACCEPTED;
}
break;
}
case MAV_CMD_DO_SEND_BANNER: {
result = MAV_RESULT_ACCEPTED;
@ -1591,10 +1583,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
#endif
break;
case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
send_autopilot_version(FIRMWARE_VERSION);
break;
case MAVLINK_MSG_ID_SET_HOME_POSITION:
{
mavlink_set_home_position_t packet;
@ -1780,3 +1768,8 @@ bool GCS_MAVLINK_Copter::set_mode(const uint8_t mode)
#endif
return copter.set_mode((control_mode_t)mode, MODE_REASON_GCS_COMMAND);
}
const AP_FWVersion &GCS_MAVLINK_Copter::get_fwver() const
{
return copter.fwver;
}

View File

@ -26,6 +26,7 @@ protected:
AP_GPS *get_gps() const override;
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
const AP_FWVersion &get_fwver() const override;
uint8_t sysid_my_gcs() const override;