mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_MotorsHeli: Change SV_MAN=2=Center to output _col_mid_pwm instead of 0 collective
This commit is contained in:
parent
246583dc06
commit
146c0319a7
@ -259,7 +259,7 @@ void AP_MotorsHeli::output_disarmed()
|
||||
// fixate mid collective
|
||||
_roll_control_input = 0;
|
||||
_pitch_control_input = 0;
|
||||
_throttle_control_input = 500;
|
||||
_throttle_control_input = _collective_mid_pwm;
|
||||
_yaw_control_input = 0;
|
||||
break;
|
||||
case SERVO_CONTROL_MODE_MANUAL_MAX:
|
||||
|
Loading…
Reference in New Issue
Block a user