Rover: handle common GPS messages in base GCS_MAVLINK class

This commit is contained in:
Peter Barker 2017-07-25 17:06:36 +10:00 committed by Francisco Ferreira
parent f1ab50d4ea
commit fec152385c
2 changed files with 6 additions and 8 deletions

View File

@ -1298,14 +1298,6 @@ void GCS_MAVLINK_Rover::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:
{
rover.gps.handle_msg(msg);
break;
}
#if HIL_MODE != HIL_MODE_DISABLED
case MAVLINK_MSG_ID_HIL_STATE:
{
@ -1503,6 +1495,11 @@ bool GCS_MAVLINK_Rover::accept_packet(const mavlink_status_t &status, mavlink_me
return (msg.sysid == rover.g.sysid_my_gcs);
}
AP_GPS *GCS_MAVLINK_Rover::get_gps() const
{
return &rover.gps;
}
AP_ServoRelayEvents *GCS_MAVLINK_Rover::get_servorelayevents() const
{
return &rover.ServoRelayEvents;

View File

@ -20,6 +20,7 @@ protected:
AP_Mission *get_mission() override;
AP_Rally *get_rally() const override { return nullptr; };
AP_ServoRelayEvents *get_servorelayevents() const override;
AP_GPS *get_gps() const override;
uint8_t sysid_my_gcs() const override;