AP_MotorsTri: get rid of _motor_to_channel_map

This commit is contained in:
Lucas De Marchi 2015-09-29 12:01:12 +09:00 committed by Randy Mackay
parent 1572c9d4f4
commit 537599c01b
1 changed files with 21 additions and 21 deletions

View File

@ -94,9 +94,9 @@ void AP_MotorsTri::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_4]);
1U << AP_MOTORS_MOT_1 |
1U << AP_MOTORS_MOT_2 |
1U << AP_MOTORS_MOT_4;
hal.rcout->set_freq(mask, _speed_hz);
}
@ -104,9 +104,9 @@ void AP_MotorsTri::set_update_rate( uint16_t speed_hz )
void AP_MotorsTri::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_4]));
hal.rcout->enable_ch(AP_MOTORS_MOT_1);
hal.rcout->enable_ch(AP_MOTORS_MOT_2);
hal.rcout->enable_ch(AP_MOTORS_MOT_4);
hal.rcout->enable_ch(AP_MOTORS_CH_TRI_YAW);
}
@ -117,9 +117,9 @@ void AP_MotorsTri::output_min()
limit.throttle_lower = true;
// send minimum value to each motor
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), _throttle_radio_min);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), _throttle_radio_min);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), _throttle_radio_min);
hal.rcout->write(AP_MOTORS_MOT_1, _throttle_radio_min);
hal.rcout->write(AP_MOTORS_MOT_2, _throttle_radio_min);
hal.rcout->write(AP_MOTORS_MOT_4, _throttle_radio_min);
hal.rcout->write(AP_MOTORS_CH_TRI_YAW, _yaw_servo_trim);
}
@ -128,9 +128,9 @@ void AP_MotorsTri::output_min()
uint16_t AP_MotorsTri::get_motor_mask()
{
// tri copter uses channels 1,2,4 and 7
return (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_4])) |
return (1U << AP_MOTORS_MOT_1) |
(1U << AP_MOTORS_MOT_2) |
(1U << AP_MOTORS_MOT_4) |
(1U << AP_MOTORS_CH_TRI_YAW);
}
@ -172,9 +172,9 @@ void AP_MotorsTri::output_armed_not_stabilizing()
}
// send output to each motor
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), motor_out[AP_MOTORS_MOT_1]);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), motor_out[AP_MOTORS_MOT_2]);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), motor_out[AP_MOTORS_MOT_4]);
hal.rcout->write(AP_MOTORS_MOT_1, motor_out[AP_MOTORS_MOT_1]);
hal.rcout->write(AP_MOTORS_MOT_2, motor_out[AP_MOTORS_MOT_2]);
hal.rcout->write(AP_MOTORS_MOT_4, motor_out[AP_MOTORS_MOT_4]);
// send centering signal to yaw servo
hal.rcout->write(AP_MOTORS_CH_TRI_YAW, _yaw_servo_trim);
@ -285,9 +285,9 @@ void AP_MotorsTri::output_armed_stabilizing()
}
// send output to each motor
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), motor_out[AP_MOTORS_MOT_1]);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), motor_out[AP_MOTORS_MOT_2]);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), motor_out[AP_MOTORS_MOT_4]);
hal.rcout->write(AP_MOTORS_MOT_1, motor_out[AP_MOTORS_MOT_1]);
hal.rcout->write(AP_MOTORS_MOT_2, motor_out[AP_MOTORS_MOT_2]);
hal.rcout->write(AP_MOTORS_MOT_4, motor_out[AP_MOTORS_MOT_4]);
// send out to yaw command to tail servo
hal.rcout->write(AP_MOTORS_CH_TRI_YAW, yaw_radio_output);
@ -314,11 +314,11 @@ void AP_MotorsTri::output_test(uint8_t motor_seq, int16_t pwm)
switch (motor_seq) {
case 1:
// front right motor
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:
// back motor
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 3:
// back servo
@ -326,7 +326,7 @@ void AP_MotorsTri::output_test(uint8_t motor_seq, int16_t pwm)
break;
case 4:
// front left motor
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), pwm);
hal.rcout->write(AP_MOTORS_MOT_2, pwm);
break;
default:
// do nothing