AP_Motors_Multi: get rid of _motor_to_channel_map
This commit is contained in:
parent
d97d97dc54
commit
7ea141b774
@ -378,9 +378,9 @@ void AP_MotorsMulticopter::throttle_pass_through(int16_t pwm)
|
||||
{
|
||||
if (armed()) {
|
||||
// send the pilot's input directly to each enabled motor
|
||||
for (int16_t i=0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||
for (uint16_t i=0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||
if (motor_enabled[i]) {
|
||||
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[i]), pwm);
|
||||
hal.rcout->write(i, pwm);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user