mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsMatrix: small bug fix to limit checking on remove_motor call. Fix thanks to Michael Peschel!
This commit is contained in:
parent
6fe0882809
commit
bec5321b8b
|
@ -306,7 +306,7 @@ void AP_MotorsMatrix::remove_motor(int8_t motor_num)
|
|||
int8_t i;
|
||||
|
||||
// ensure valid motor number is provided
|
||||
if( motor_num >= 0 && motor_num <= AP_MOTORS_MAX_NUM_MOTORS ) {
|
||||
if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
|
||||
|
||||
// if the motor was enabled decrement the number of motors
|
||||
if( motor_enabled[motor_num] )
|
||||
|
|
Loading…
Reference in New Issue