mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: move send_autopilot_request calls up to GCS base class
This commit is contained in:
parent
add1743c12
commit
bb06db6389
@ -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;
|
||||
}
|
||||
|
@ -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;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user