mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_MotorsMatrix: get rid of _motor_to_channel_map
This commit is contained in:
parent
43268b9822
commit
1572c9d4f4
@ -37,7 +37,7 @@ void AP_MotorsMatrix::Init()
|
||||
// set update rate to motors - a value in hertz
|
||||
void AP_MotorsMatrix::set_update_rate( uint16_t speed_hz )
|
||||
{
|
||||
int8_t i;
|
||||
uint8_t i;
|
||||
|
||||
// record requested speed
|
||||
_speed_hz = speed_hz;
|
||||
@ -46,7 +46,7 @@ void AP_MotorsMatrix::set_update_rate( uint16_t speed_hz )
|
||||
uint32_t mask = 0;
|
||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
||||
if( motor_enabled[i] ) {
|
||||
mask |= 1U << pgm_read_byte(&_motor_to_channel_map[i]);
|
||||
mask |= 1U << i;
|
||||
}
|
||||
}
|
||||
hal.rcout->set_freq( mask, _speed_hz );
|
||||
@ -78,7 +78,7 @@ void AP_MotorsMatrix::enable()
|
||||
// enable output channels
|
||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
||||
if( motor_enabled[i] ) {
|
||||
hal.rcout->enable_ch(pgm_read_byte(&_motor_to_channel_map[i]));
|
||||
hal.rcout->enable_ch(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -97,7 +97,7 @@ void AP_MotorsMatrix::output_min()
|
||||
// fill the motor_out[] array for HIL use and send minimum value to each motor
|
||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
||||
if( motor_enabled[i] ) {
|
||||
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[i]), _throttle_radio_min);
|
||||
hal.rcout->write(i, _throttle_radio_min);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -117,7 +117,7 @@ uint16_t AP_MotorsMatrix::get_motor_mask()
|
||||
|
||||
void AP_MotorsMatrix::output_armed_not_stabilizing()
|
||||
{
|
||||
int8_t i;
|
||||
uint8_t i;
|
||||
int16_t throttle_radio_output; // total throttle pwm value, summed onto throttle channel minimum, typically ~1100-1900
|
||||
int16_t motor_out[AP_MOTORS_MAX_NUM_MOTORS]; // final outputs sent to the motors
|
||||
int16_t out_min_pwm = _throttle_radio_min + _min_throttle; // minimum pwm value we can send to the motors
|
||||
@ -161,7 +161,7 @@ void AP_MotorsMatrix::output_armed_not_stabilizing()
|
||||
// send output to each motor
|
||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
||||
if( motor_enabled[i] ) {
|
||||
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[i]), motor_out[i]);
|
||||
hal.rcout->write(i, motor_out[i]);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -357,7 +357,7 @@ void AP_MotorsMatrix::output_armed_stabilizing()
|
||||
// send output to each motor
|
||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
||||
if( motor_enabled[i] ) {
|
||||
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[i]), motor_out[i]);
|
||||
hal.rcout->write(i, motor_out[i]);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -383,7 +383,7 @@ void AP_MotorsMatrix::output_test(uint8_t motor_seq, int16_t pwm)
|
||||
for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||
if (motor_enabled[i] && _test_order[i] == motor_seq) {
|
||||
// turn on this motor
|
||||
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[i]), pwm);
|
||||
hal.rcout->write(i, pwm);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -408,7 +408,7 @@ void AP_MotorsMatrix::add_motor_raw(int8_t motor_num, float roll_fac, float pitc
|
||||
_test_order[motor_num] = testing_order;
|
||||
|
||||
// disable this channel from being used by RC_Channel_aux
|
||||
RC_Channel_aux::disable_aux_channel(_motor_to_channel_map[motor_num]);
|
||||
RC_Channel_aux::disable_aux_channel(motor_num);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user