Plane: handle common GPS messages in base GCS_MAVLINK class

This commit is contained in:
Peter Barker 2017-07-25 17:08:40 +10:00 committed by Francisco Ferreira
parent d3c5369352
commit 87af817893
2 changed files with 6 additions and 8 deletions

View File

@ -1604,14 +1604,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
break;
}
case MAVLINK_MSG_ID_GPS_RTCM_DATA:
case MAVLINK_MSG_ID_GPS_INPUT:
case MAVLINK_MSG_ID_HIL_GPS:
{
plane.gps.handle_msg(msg);
break;
}
case MAVLINK_MSG_ID_HIL_STATE:
{
#if HIL_SUPPORT
@ -2011,6 +2003,11 @@ void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, mavlink_
}
}
AP_GPS *GCS_MAVLINK_Plane::get_gps() const
{
return &plane.gps;
}
AP_ServoRelayEvents *GCS_MAVLINK_Plane::get_servorelayevents() const
{
return &plane.ServoRelayEvents;

View File

@ -24,6 +24,7 @@ protected:
Compass *get_compass() const override;
AP_ServoRelayEvents *get_servorelayevents() const override;
AP_Rally *get_rally() const override;
AP_GPS *get_gps() const override;
uint8_t sysid_my_gcs() const override;