GCS_MAVLink: allow compilation when GPS library not available
This commit is contained in:
parent
fa4c7d8eb0
commit
33b0bf699e
@ -2756,6 +2756,7 @@ void GCS_MAVLINK::send_named_float(const char *name, float value) const
|
||||
mavlink_msg_named_value_float_send(chan, AP_HAL::millis(), float_name, value);
|
||||
}
|
||||
|
||||
#if AP_AHRS_ENABLED
|
||||
void GCS_MAVLINK::send_home_position() const
|
||||
{
|
||||
if (!AP::ahrs().home_is_set()) {
|
||||
@ -2801,6 +2802,7 @@ void GCS_MAVLINK::send_gps_global_origin() const
|
||||
ekf_origin.alt * 10,
|
||||
AP_HAL::micros64());
|
||||
}
|
||||
#endif // AP_AHRS_ENABLED
|
||||
|
||||
MAV_STATE GCS_MAVLINK::system_status() const
|
||||
{
|
||||
@ -5652,6 +5654,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
send_global_position_int();
|
||||
break;
|
||||
|
||||
#if AP_AHRS_ENABLED
|
||||
case MSG_HOME:
|
||||
CHECK_PAYLOAD_SIZE(HOME_POSITION);
|
||||
send_home_position();
|
||||
@ -5661,6 +5664,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
CHECK_PAYLOAD_SIZE(GPS_GLOBAL_ORIGIN);
|
||||
send_gps_global_origin();
|
||||
break;
|
||||
#endif // AP_AHRS_ENABLED
|
||||
|
||||
#if AP_RPM_ENABLED
|
||||
case MSG_RPM:
|
||||
|
Loading…
Reference in New Issue
Block a user