mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Motors: fixed use of trim on heli servos
this was broken by the servo range 0 to 1 changes
This commit is contained in:
parent
0cd3054a4c
commit
7cd7f03d56
@ -454,10 +454,15 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
|
||||
|
||||
hal.rcout->cork();
|
||||
|
||||
// rescale from -1..1, so we can use the pwm calc that includes trim
|
||||
servo1_out = 2*servo1_out - 1;
|
||||
servo2_out = 2*servo2_out - 1;
|
||||
servo3_out = 2*servo3_out - 1;
|
||||
|
||||
// actually move the servos
|
||||
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_0to1(servo1_out, _swash_servo_1));
|
||||
rc_write(AP_MOTORS_MOT_2, calc_pwm_output_0to1(servo2_out, _swash_servo_2));
|
||||
rc_write(AP_MOTORS_MOT_3, calc_pwm_output_0to1(servo3_out, _swash_servo_3));
|
||||
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(servo1_out, _swash_servo_1));
|
||||
rc_write(AP_MOTORS_MOT_2, calc_pwm_output_1to1(servo2_out, _swash_servo_2));
|
||||
rc_write(AP_MOTORS_MOT_3, calc_pwm_output_1to1(servo3_out, _swash_servo_3));
|
||||
|
||||
// update the yaw rate using the tail rotor/servo
|
||||
move_yaw(yaw_out + yaw_offset);
|
||||
|
Loading…
Reference in New Issue
Block a user