mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Tracker: move send_autopilot_request calls up to GCS base class
This commit is contained in:
parent
52463a5ed6
commit
98f9e744b0
@ -582,14 +582,6 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
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_ACCELCAL_VEHICLE_POS:
|
case MAV_CMD_ACCELCAL_VEHICLE_POS:
|
||||||
result = MAV_RESULT_FAILED;
|
result = MAV_RESULT_FAILED;
|
||||||
|
|
||||||
@ -740,10 +732,6 @@ mission_failed:
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
|
|
||||||
send_autopilot_version(FIRMWARE_VERSION);
|
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
handle_common_message(msg);
|
handle_common_message(msg);
|
||||||
break;
|
break;
|
||||||
@ -838,6 +826,11 @@ bool GCS_MAVLINK_Tracker::set_mode(uint8_t mode)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
const AP_FWVersion &GCS_MAVLINK_Tracker::get_fwver() const
|
||||||
|
{
|
||||||
|
return tracker.fwver;
|
||||||
|
}
|
||||||
|
|
||||||
/* dummy methods to avoid having to link against AP_Camera */
|
/* dummy methods to avoid having to link against AP_Camera */
|
||||||
void AP_Camera::control_msg(mavlink_message_t const*) {}
|
void AP_Camera::control_msg(mavlink_message_t const*) {}
|
||||||
void AP_Camera::configure(float, float, float, float, float, float, float) {}
|
void AP_Camera::configure(float, float, float, float, float, float, float) {}
|
||||||
|
@ -22,6 +22,7 @@ protected:
|
|||||||
AP_Camera *get_camera() const override { return nullptr; };
|
AP_Camera *get_camera() const override { return nullptr; };
|
||||||
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
||||||
AP_GPS *get_gps() const override;
|
AP_GPS *get_gps() const override;
|
||||||
|
const AP_FWVersion &get_fwver() const override;
|
||||||
|
|
||||||
uint8_t sysid_my_gcs() const override;
|
uint8_t sysid_my_gcs() const override;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user