Copter: handle common GPS messages in base GCS_MAVLINK class

This commit is contained in:
Peter Barker 2017-07-25 17:10:14 +10:00 committed by Francisco Ferreira
parent 85a0da6178
commit f1ab50d4ea
2 changed files with 6 additions and 9 deletions

View File

@ -1624,15 +1624,6 @@ void GCS_MAVLINK_Copter::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:
{
result = MAV_RESULT_ACCEPTED;
copter.gps.handle_msg(msg);
break;
}
#if HIL_MODE != HIL_MODE_DISABLED
case MAVLINK_MSG_ID_HIL_STATE: // MAV ID: 90
{
@ -1874,6 +1865,11 @@ Compass *GCS_MAVLINK_Copter::get_compass() const
return &copter.compass;
}
AP_GPS *GCS_MAVLINK_Copter::get_gps() const
{
return &copter.gps;
}
AP_ServoRelayEvents *GCS_MAVLINK_Copter::get_servorelayevents() const
{
return &copter.ServoRelayEvents;

View File

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