mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: tidy sending of WATER_DEPTH messages
This commit is contained in:
parent
1059183758
commit
031e5b1dab
|
@ -1045,7 +1045,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
|
||||||
#if HAL_WITH_ESC_TELEM
|
#if HAL_WITH_ESC_TELEM
|
||||||
{ MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, MSG_ESC_TELEMETRY},
|
{ MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, MSG_ESC_TELEMETRY},
|
||||||
#endif
|
#endif
|
||||||
#if APM_BUILD_TYPE(APM_BUILD_Rover)
|
#if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||||
{ MAVLINK_MSG_ID_WATER_DEPTH, MSG_WATER_DEPTH},
|
{ MAVLINK_MSG_ID_WATER_DEPTH, MSG_WATER_DEPTH},
|
||||||
#endif
|
#endif
|
||||||
#if HAL_HIGH_LATENCY2_ENABLED
|
#if HAL_HIGH_LATENCY2_ENABLED
|
||||||
|
@ -6028,12 +6028,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case MSG_WATER_DEPTH:
|
|
||||||
#if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover)
|
#if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||||
|
case MSG_WATER_DEPTH:
|
||||||
CHECK_PAYLOAD_SIZE(WATER_DEPTH);
|
CHECK_PAYLOAD_SIZE(WATER_DEPTH);
|
||||||
send_water_depth();
|
send_water_depth();
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
case MSG_HIGH_LATENCY2:
|
case MSG_HIGH_LATENCY2:
|
||||||
#if HAL_HIGH_LATENCY2_ENABLED
|
#if HAL_HIGH_LATENCY2_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue