AP_MotorsSingle: get rid of _motor_to_channel_map

This commit is contained in:
Lucas De Marchi 2015-09-29 12:01:25 +09:00 committed by Randy Mackay
parent 537599c01b
commit ec4ebfde83

View File

@ -92,35 +92,35 @@ void AP_MotorsSingle::set_update_rate( uint16_t speed_hz )
// set update rate for the 3 motors (but not the servo on channel 7)
uint32_t mask =
1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]) |
1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]) |
1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]) |
1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]) ;
1U << AP_MOTORS_MOT_1 |
1U << AP_MOTORS_MOT_2 |
1U << AP_MOTORS_MOT_3 |
1U << AP_MOTORS_MOT_4 ;
hal.rcout->set_freq(mask, _servo_speed);
uint32_t mask2 = 1U << pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_7]);
hal.rcout->set_freq(mask2, _speed_hz);
uint32_t mask2 = 1U << AP_MOTORS_MOT_7;
hal.rcout->set_freq(mask2, _speed_hz);
}
// enable - starts allowing signals to be sent to motors
void AP_MotorsSingle::enable()
{
// enable output channels
hal.rcout->enable_ch(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]));
hal.rcout->enable_ch(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]));
hal.rcout->enable_ch(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]));
hal.rcout->enable_ch(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]));
hal.rcout->enable_ch(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_7]));
hal.rcout->enable_ch(AP_MOTORS_MOT_1);
hal.rcout->enable_ch(AP_MOTORS_MOT_2);
hal.rcout->enable_ch(AP_MOTORS_MOT_3);
hal.rcout->enable_ch(AP_MOTORS_MOT_4);
hal.rcout->enable_ch(AP_MOTORS_MOT_7);
}
// output_min - sends minimum values out to the motor and trim values to the servos
void AP_MotorsSingle::output_min()
{
// send minimum value to each motor
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), _servo1.radio_trim);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), _servo2.radio_trim);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]), _servo3.radio_trim);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), _servo4.radio_trim);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_7]), _throttle_radio_min);
hal.rcout->write(AP_MOTORS_MOT_1, _servo1.radio_trim);
hal.rcout->write(AP_MOTORS_MOT_2, _servo2.radio_trim);
hal.rcout->write(AP_MOTORS_MOT_3, _servo3.radio_trim);
hal.rcout->write(AP_MOTORS_MOT_4, _servo4.radio_trim);
hal.rcout->write(AP_MOTORS_MOT_7, _throttle_radio_min);
}
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
@ -172,11 +172,11 @@ void AP_MotorsSingle::output_armed_not_stabilizing()
throttle_radio_output = apply_thrust_curve_and_volt_scaling(throttle_radio_output, out_min, _throttle_radio_max);
}
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), _servo1.radio_out);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), _servo2.radio_out);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]), _servo3.radio_out);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), _servo4.radio_out);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_7]), throttle_radio_output);
hal.rcout->write(AP_MOTORS_MOT_1, _servo1.radio_out);
hal.rcout->write(AP_MOTORS_MOT_2, _servo2.radio_out);
hal.rcout->write(AP_MOTORS_MOT_3, _servo3.radio_out);
hal.rcout->write(AP_MOTORS_MOT_4, _servo4.radio_out);
hal.rcout->write(AP_MOTORS_MOT_7, throttle_radio_output);
}
// sends commands to the motors
@ -229,11 +229,11 @@ void AP_MotorsSingle::output_armed_stabilizing()
_servo4.calc_pwm();
// send output to each motor
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), _servo1.radio_out);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), _servo2.radio_out);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]), _servo3.radio_out);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), _servo4.radio_out);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_7]), throttle_radio_output);
hal.rcout->write(AP_MOTORS_MOT_1, _servo1.radio_out);
hal.rcout->write(AP_MOTORS_MOT_2, _servo2.radio_out);
hal.rcout->write(AP_MOTORS_MOT_3, _servo3.radio_out);
hal.rcout->write(AP_MOTORS_MOT_4, _servo4.radio_out);
hal.rcout->write(AP_MOTORS_MOT_7, throttle_radio_output);
}
// output_disarmed - sends commands to the motors
@ -257,23 +257,23 @@ void AP_MotorsSingle::output_test(uint8_t motor_seq, int16_t pwm)
switch (motor_seq) {
case 1:
// flap servo 1
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), pwm);
hal.rcout->write(AP_MOTORS_MOT_1, pwm);
break;
case 2:
// flap servo 2
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), pwm);
hal.rcout->write(AP_MOTORS_MOT_2, pwm);
break;
case 3:
// flap servo 3
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]), pwm);
hal.rcout->write(AP_MOTORS_MOT_3, pwm);
break;
case 4:
// flap servo 4
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), pwm);
hal.rcout->write(AP_MOTORS_MOT_4, pwm);
break;
case 5:
// spin main motor
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_7]), pwm);
hal.rcout->write(AP_MOTORS_MOT_7, pwm);
break;
default:
// do nothing