Plane: move send_autopilot_request calls up to GCS base class

This commit is contained in:
Peter Barker 2017-08-19 19:51:00 +10:00 committed by Francisco Ferreira
parent bb06db6389
commit 0db1711b1f
2 changed files with 6 additions and 11 deletions

View File

@ -1272,13 +1272,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
}
break;
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_SET_HOME: {
// param1 : use current (1=use current location, 0=use specified location)
// param5 : latitude
@ -1594,10 +1587,6 @@ void GCS_MAVLINK_Plane::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_ATTITUDE_TARGET:
{
// Only allow companion computer (or other external controller) to
@ -1920,3 +1909,8 @@ bool GCS_MAVLINK_Plane::set_mode(const uint8_t mode)
}
return false;
}
const AP_FWVersion &GCS_MAVLINK_Plane::get_fwver() const
{
return plane.fwver;
}

View File

@ -27,6 +27,7 @@ protected:
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
AP_Rally *get_rally() const override;
AP_GPS *get_gps() const override;
const AP_FWVersion &get_fwver() const override;
uint8_t sysid_my_gcs() const override;