mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 09:33:59 -03:00
Sub: cleanup depth hold
Remove block of code that is replicated in the flight mode init()
This commit is contained in:
parent
ddd0119ccc
commit
265d848021
@ -33,20 +33,6 @@ void Sub::handle_attitude()
|
||||
{
|
||||
uint32_t tnow = AP_HAL::millis();
|
||||
|
||||
// initialize vertical speeds and acceleration
|
||||
pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
||||
pos_control.set_max_accel_z(g.pilot_accel_z);
|
||||
|
||||
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.relax_attitude_controllers();
|
||||
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
||||
last_pilot_heading = ahrs.yaw_sensor;
|
||||
return;
|
||||
}
|
||||
|
||||
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
|
||||
// get pilot desired lean angles
|
||||
|
Loading…
Reference in New Issue
Block a user