mirror of https://github.com/ArduPilot/ardupilot
AP_BLHeli: fix watchdog resets with telemetry active from non-multirotor motors
This commit is contained in:
parent
185475d689
commit
b89c60d5b0
|
@ -1274,7 +1274,7 @@ void AP_BLHeli::update(void)
|
||||||
motor_mask = mask;
|
motor_mask = mask;
|
||||||
debug("ESC: %u motors mask=0x%04x", num_motors, mask);
|
debug("ESC: %u motors mask=0x%04x", num_motors, mask);
|
||||||
|
|
||||||
if (telem_rate > 0) {
|
if (num_motors != 0 && telem_rate > 0) {
|
||||||
AP_SerialManager *serial_manager = AP_SerialManager::get_singleton();
|
AP_SerialManager *serial_manager = AP_SerialManager::get_singleton();
|
||||||
if (serial_manager) {
|
if (serial_manager) {
|
||||||
telem_uart = serial_manager->find_serial(AP_SerialManager::SerialProtocol_ESCTelemetry,0);
|
telem_uart = serial_manager->find_serial(AP_SerialManager::SerialProtocol_ESCTelemetry,0);
|
||||||
|
|
Loading…
Reference in New Issue