mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
Sub: Fix throttle value in some calls to
pos_control.relax_alt_hold_controllers
This commit is contained in:
parent
a83e1ad971
commit
7a6318434f
@ -649,7 +649,7 @@ bool Sub::auto_terrain_recover_start()
|
|||||||
wp_nav.init_loiter_target();
|
wp_nav.init_loiter_target();
|
||||||
|
|
||||||
// Reset z axis controller
|
// Reset z axis controller
|
||||||
pos_control.relax_alt_hold_controllers(0.0);
|
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
||||||
|
|
||||||
// initialize vertical speeds and leash lengths
|
// initialize vertical speeds and leash lengths
|
||||||
pos_control.set_speed_z(wp_nav.get_speed_down(), wp_nav.get_speed_up());
|
pos_control.set_speed_z(wp_nav.get_speed_down(), wp_nav.get_speed_up());
|
||||||
@ -699,7 +699,7 @@ void Sub::auto_terrain_recover_run()
|
|||||||
// Start timer as soon as rangefinder is healthy
|
// Start timer as soon as rangefinder is healthy
|
||||||
if (rangefinder_recovery_ms == 0) {
|
if (rangefinder_recovery_ms == 0) {
|
||||||
rangefinder_recovery_ms = AP_HAL::millis();
|
rangefinder_recovery_ms = AP_HAL::millis();
|
||||||
pos_control.relax_alt_hold_controllers(0.0); // Reset alt hold targets
|
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover()); // Reset alt hold targets
|
||||||
}
|
}
|
||||||
|
|
||||||
// 1.5 seconds of healthy rangefinder means we can resume mission with terrain enabled
|
// 1.5 seconds of healthy rangefinder means we can resume mission with terrain enabled
|
||||||
|
@ -462,7 +462,7 @@ void Sub::guided_angle_control_run()
|
|||||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||||
attitude_control.set_throttle_out_unstabilized(0.0f,true,g.throttle_filt);
|
attitude_control.set_throttle_out_unstabilized(0.0f,true,g.throttle_filt);
|
||||||
|
|
||||||
pos_control.relax_alt_hold_controllers(0.0f);
|
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user