mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tracker: handle common GPS messages in base GCS_MAVLINK class
This commit is contained in:
parent
fec152385c
commit
d3c5369352
@ -817,12 +817,6 @@ mission_failed:
|
|||||||
handle_gps_inject(msg, tracker.gps);
|
handle_gps_inject(msg, tracker.gps);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_GPS_RTCM_DATA:
|
|
||||||
case MAVLINK_MSG_ID_GPS_INPUT:
|
|
||||||
case MAVLINK_MSG_ID_HIL_GPS:
|
|
||||||
tracker.gps.handle_msg(msg);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
|
case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
|
||||||
send_autopilot_version(FIRMWARE_VERSION);
|
send_autopilot_version(FIRMWARE_VERSION);
|
||||||
break;
|
break;
|
||||||
@ -895,6 +889,11 @@ void Tracker::gcs_retry_deferred(void)
|
|||||||
gcs().service_statustext();
|
gcs().service_statustext();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
AP_GPS *GCS_MAVLINK_Tracker::get_gps() const
|
||||||
|
{
|
||||||
|
return &tracker.gps;
|
||||||
|
}
|
||||||
|
|
||||||
Compass *GCS_MAVLINK_Tracker::get_compass() const
|
Compass *GCS_MAVLINK_Tracker::get_compass() const
|
||||||
{
|
{
|
||||||
return &tracker.compass;
|
return &tracker.compass;
|
||||||
|
@ -20,6 +20,7 @@ protected:
|
|||||||
AP_Mission *get_mission() override { return nullptr; };
|
AP_Mission *get_mission() override { return nullptr; };
|
||||||
AP_Rally *get_rally() const override { return nullptr; };
|
AP_Rally *get_rally() 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;
|
||||||
|
|
||||||
uint8_t sysid_my_gcs() const override;
|
uint8_t sysid_my_gcs() const override;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user