mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Sub: move send_autopilot_request calls up to GCS base class
This commit is contained in:
parent
0db1711b1f
commit
52463a5ed6
@ -1260,14 +1260,6 @@ void GCS_MAVLINK_Sub::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;
|
||||
|
||||
@ -1507,10 +1499,6 @@ void GCS_MAVLINK_Sub::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;
|
||||
mavlink_msg_set_home_position_decode(msg, &packet);
|
||||
@ -1657,5 +1645,10 @@ bool GCS_MAVLINK_Sub::set_mode(uint8_t mode)
|
||||
return sub.set_mode((control_mode_t)mode, MODE_REASON_GCS_COMMAND);
|
||||
}
|
||||
|
||||
const AP_FWVersion &GCS_MAVLINK_Sub::get_fwver() const
|
||||
{
|
||||
return sub.fwver;
|
||||
}
|
||||
|
||||
// dummy method to avoid linking AFS
|
||||
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate) { return false; }
|
||||
|
@ -20,6 +20,7 @@ protected:
|
||||
AP_Camera *get_camera() const override;
|
||||
AP_ServoRelayEvents *get_servorelayevents() const override;
|
||||
AP_GPS *get_gps() const override;
|
||||
const AP_FWVersion &get_fwver() const override;
|
||||
|
||||
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user