mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: move send_autopilot_request calls up to GCS base class
This commit is contained in:
parent
98f9e744b0
commit
85ac69f701
@ -860,14 +860,6 @@ void GCS_MAVLINK_Rover::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)
|
||||
@ -1278,10 +1270,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
||||
rover.rangefinder.handle_msg(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
|
||||
send_autopilot_version(FIRMWARE_VERSION);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_VISION_POSITION_DELTA:
|
||||
rover.g2.visual_odom.handle_msg(msg);
|
||||
break;
|
||||
@ -1415,3 +1403,8 @@ bool GCS_MAVLINK_Rover::set_mode(const uint8_t mode)
|
||||
}
|
||||
return rover.set_mode(*new_mode, MODE_REASON_GCS_COMMAND);
|
||||
}
|
||||
|
||||
const AP_FWVersion &GCS_MAVLINK_Rover::get_fwver() const
|
||||
{
|
||||
return rover.fwver;
|
||||
}
|
||||
|
@ -23,6 +23,7 @@ protected:
|
||||
AP_ServoRelayEvents *get_servorelayevents() const override;
|
||||
AP_GPS *get_gps() const 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