mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
GCS_MAVLink: save bytes when AP_AIS_ENABLED is false
This commit is contained in:
parent
0928927ab7
commit
d665d2c56e
@ -5987,16 +5987,15 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
break;
|
||||
|
||||
case MSG_AIS_VESSEL: {
|
||||
#if AP_AIS_ENABLED
|
||||
case MSG_AIS_VESSEL: {
|
||||
AP_AIS *ais = AP_AIS::get_singleton();
|
||||
if (ais) {
|
||||
ais->send(chan);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
case MSG_UAVIONIX_ADSB_OUT_STATUS:
|
||||
#if HAL_ADSB_ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user