mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: fix position ctrl init for guided takeof
This commit is contained in:
parent
1dafa2ba9c
commit
d050df5629
@ -541,6 +541,8 @@ void Mode::make_safe_ground_handling(bool force_throttle_unlimited)
|
||||
break;
|
||||
}
|
||||
|
||||
pos_control->relax_velocity_controller_xy();
|
||||
pos_control->update_xy_controller();
|
||||
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
|
||||
pos_control->update_z_controller();
|
||||
// we may need to move this out
|
||||
|
@ -892,7 +892,6 @@ void ModeAuto::wp_run()
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (is_disarmed_or_landed()) {
|
||||
make_safe_ground_handling();
|
||||
wp_nav->wp_and_spline_init();
|
||||
return;
|
||||
}
|
||||
|
||||
@ -989,7 +988,6 @@ void ModeAuto::loiter_run()
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (is_disarmed_or_landed()) {
|
||||
make_safe_ground_handling();
|
||||
wp_nav->wp_and_spline_init();
|
||||
return;
|
||||
}
|
||||
|
||||
@ -1015,7 +1013,7 @@ void ModeAuto::loiter_to_alt_run()
|
||||
{
|
||||
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
|
||||
if (is_disarmed_or_landed() || !motors->get_interlock()) {
|
||||
zero_throttle_and_relax_ac();
|
||||
make_safe_ground_handling();
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -37,7 +37,6 @@ void ModeBrake::run()
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (is_disarmed_or_landed()) {
|
||||
make_safe_ground_handling();
|
||||
pos_control->relax_velocity_controller_xy();
|
||||
pos_control->relax_z_controller(0.0f);
|
||||
return;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user