mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_MotorsHeli: Yaw servo to move when using SV_MAN param for setup.
This commit is contained in:
parent
146c0319a7
commit
0228a99d4e
@ -267,14 +267,14 @@ void AP_MotorsHeli::output_disarmed()
|
||||
_roll_control_input = 0;
|
||||
_pitch_control_input = 0;
|
||||
_throttle_control_input = 1000;
|
||||
_yaw_control_input = 0;
|
||||
_yaw_control_input = 4500;
|
||||
break;
|
||||
case SERVO_CONTROL_MODE_MANUAL_MIN:
|
||||
// fixate min collective
|
||||
_roll_control_input = 0;
|
||||
_pitch_control_input = 0;
|
||||
_throttle_control_input = 0;
|
||||
_yaw_control_input = 0;
|
||||
_yaw_control_input = -4500;
|
||||
break;
|
||||
default:
|
||||
// no manual override
|
||||
|
Loading…
Reference in New Issue
Block a user