Browse Source

AP_BLHeli: fixed use of SERVO_BLH_AUTO

master
Andrew Tridgell 7 years ago
parent
commit
6f704b3818
  1. 10
      libraries/AP_BLHeli/AP_BLHeli.cpp

10
libraries/AP_BLHeli/AP_BLHeli.cpp

@ -409,7 +409,7 @@ void AP_BLHeli::msp_process_command(void)
msp.escMode = (enum escProtocol)msp.buf[0]; msp.escMode = (enum escProtocol)msp.buf[0];
msp.portIndex = msp.buf[1]; msp.portIndex = msp.buf[1];
} }
debug("escMode=%u portIndex=%u", msp.escMode, msp.portIndex); debug("escMode=%u portIndex=%u num_motors=%u", msp.escMode, msp.portIndex, num_motors);
uint8_t n = num_motors; uint8_t n = num_motors;
switch (msp.escMode) { switch (msp.escMode) {
case PROTOCOL_4WAY: case PROTOCOL_4WAY:
@ -1128,9 +1128,11 @@ void AP_BLHeli::update(void)
/* /*
plane and copter can use AP_Motors to get an automatic mask plane and copter can use AP_Motors to get an automatic mask
*/ */
AP_Motors *motors = AP_Motors::get_instance(); if (channel_auto.get() == 1) {
if (motors) { AP_Motors *motors = AP_Motors::get_instance();
mask |= motors->get_motor_mask(); if (motors) {
mask |= motors->get_motor_mask();
}
} }
#endif #endif

Loading…
Cancel
Save