mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Sub: Center throttle instead of zero-ing it in depth hold
This was causing the vehicle to dive when the alt-hold was disabled and subsequently enabled. Probably because the filter was holding the throttle down.
This commit is contained in:
parent
deccd051a0
commit
2af2a1ed05
@ -85,7 +85,7 @@ void Sub::althold_run()
|
||||
if (!motors.armed()) {
|
||||
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
||||
// Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
|
||||
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||
attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
|
||||
attitude_control.relax_attitude_controllers();
|
||||
pos_control.relax_alt_hold_controllers();
|
||||
last_roll = ahrs.roll_sensor;
|
||||
|
Loading…
Reference in New Issue
Block a user