mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
GCS_MAVLink: tidy use of GPS mavlink defines
This commit is contained in:
parent
1c7eebec3a
commit
fbbadecfe3
@ -3069,10 +3069,14 @@ float GCS_MAVLINK::vfr_hud_airspeed() const
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AP_GPS_ENABLED
|
||||
// because most vehicles don't have airspeed sensors, we return a
|
||||
// different sort of speed estimate in the relevant field for
|
||||
// comparison's sake.
|
||||
return AP::gps().ground_speed();
|
||||
#endif
|
||||
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
float GCS_MAVLINK::vfr_hud_climbrate() const
|
||||
@ -3977,12 +3981,14 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if AP_GPS_ENABLED
|
||||
case MAVLINK_MSG_ID_GPS_RTCM_DATA:
|
||||
case MAVLINK_MSG_ID_GPS_INPUT:
|
||||
case MAVLINK_MSG_ID_HIL_GPS:
|
||||
case MAVLINK_MSG_ID_GPS_INJECT_DATA:
|
||||
AP::gps().handle_msg(msg);
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MAVLINK_MSG_ID_STATUSTEXT:
|
||||
handle_statustext(msg);
|
||||
@ -5760,6 +5766,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
CHECK_PAYLOAD_SIZE(SYSTEM_TIME);
|
||||
send_system_time();
|
||||
break;
|
||||
#if AP_GPS_ENABLED
|
||||
case MSG_GPS_RAW:
|
||||
CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
|
||||
AP::gps().send_mavlink_gps_raw(chan);
|
||||
@ -5768,18 +5775,19 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
CHECK_PAYLOAD_SIZE(GPS_RTK);
|
||||
AP::gps().send_mavlink_gps_rtk(chan, 0);
|
||||
break;
|
||||
case MSG_GPS2_RAW:
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
case MSG_GPS2_RAW:
|
||||
CHECK_PAYLOAD_SIZE(GPS2_RAW);
|
||||
AP::gps().send_mavlink_gps2_raw(chan);
|
||||
#endif
|
||||
break;
|
||||
case MSG_GPS2_RTK:
|
||||
#endif
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
case MSG_GPS2_RTK:
|
||||
CHECK_PAYLOAD_SIZE(GPS2_RTK);
|
||||
AP::gps().send_mavlink_gps_rtk(chan, 1);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
#endif // AP_GPS_ENABLED
|
||||
case MSG_LOCAL_POSITION:
|
||||
CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED);
|
||||
send_local_position();
|
||||
|
Loading…
Reference in New Issue
Block a user