mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: fixed error in SITL for ESC_TELEMETRY
This commit is contained in:
parent
5eab425065
commit
f401dc1a77
|
@ -2988,16 +2988,16 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||||
send_vibration();
|
send_vibration();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef HAVE_AP_BLHELI_SUPPORT
|
|
||||||
case MSG_ESC_TELEMETRY: {
|
case MSG_ESC_TELEMETRY: {
|
||||||
|
#ifdef HAVE_AP_BLHELI_SUPPORT
|
||||||
CHECK_PAYLOAD_SIZE(ESC_TELEMETRY_1_TO_4);
|
CHECK_PAYLOAD_SIZE(ESC_TELEMETRY_1_TO_4);
|
||||||
AP_BLHeli *blheli = AP_BLHeli::get_singleton();
|
AP_BLHeli *blheli = AP_BLHeli::get_singleton();
|
||||||
if (blheli) {
|
if (blheli) {
|
||||||
blheli->send_esc_telemetry_mavlink(uint8_t(chan));
|
blheli->send_esc_telemetry_mavlink(uint8_t(chan));
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
// try_send_message must always at some stage return true for
|
// try_send_message must always at some stage return true for
|
||||||
|
|
Loading…
Reference in New Issue