AP_Motors: Missed Single fix
This commit is contained in:
parent
ad4d23c34d
commit
a16018f9fe
@ -121,10 +121,10 @@ void AP_MotorsSingle::output_to_motors()
|
||||
case SHUT_DOWN:
|
||||
// sends minimum values out to the motors
|
||||
hal.rcout->cork();
|
||||
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(_roll_radio_passthrough+_yaw_radio_passthrough, _servo1));
|
||||
rc_write(AP_MOTORS_MOT_2, calc_pwm_output_1to1(_pitch_radio_passthrough+_yaw_radio_passthrough, _servo2));
|
||||
rc_write(AP_MOTORS_MOT_3, calc_pwm_output_1to1(-_roll_radio_passthrough+_yaw_radio_passthrough, _servo3));
|
||||
rc_write(AP_MOTORS_MOT_4, calc_pwm_output_1to1(-_pitch_radio_passthrough+_yaw_radio_passthrough, _servo4));
|
||||
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(_roll_radio_passthrough - _yaw_radio_passthrough, _servo1));
|
||||
rc_write(AP_MOTORS_MOT_2, calc_pwm_output_1to1(_pitch_radio_passthrough - _yaw_radio_passthrough, _servo2));
|
||||
rc_write(AP_MOTORS_MOT_3, calc_pwm_output_1to1(-_roll_radio_passthrough - _yaw_radio_passthrough, _servo3));
|
||||
rc_write(AP_MOTORS_MOT_4, calc_pwm_output_1to1(-_pitch_radio_passthrough - _yaw_radio_passthrough, _servo4));
|
||||
rc_write(AP_MOTORS_MOT_5, get_pwm_output_min());
|
||||
rc_write(AP_MOTORS_MOT_6, get_pwm_output_min());
|
||||
hal.rcout->push();
|
||||
|
Loading…
Reference in New Issue
Block a user