mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Rover: loiter slows using attitude control get_desired_speed_accel_limit
This commit is contained in:
parent
fc35e74821
commit
51a0cbc1da
@ -28,11 +28,7 @@ void ModeLoiter::update()
|
||||
|
||||
// if within waypoint radius slew desired speed towards zero and use existing desired heading
|
||||
if (_distance_to_destination <= g.waypoint_radius) {
|
||||
if (is_negative(_desired_speed)) {
|
||||
_desired_speed = MIN(_desired_speed + attitude_control.get_decel_max() * rover.G_Dt, 0.0f);
|
||||
} else {
|
||||
_desired_speed = MAX(_desired_speed - attitude_control.get_decel_max() * rover.G_Dt, 0.0f);
|
||||
}
|
||||
_desired_speed = attitude_control.get_desired_speed_accel_limited(0.0f, rover.G_Dt);
|
||||
_yaw_error_cd = 0.0f;
|
||||
} else {
|
||||
// P controller with hard-coded gain to convert distance to desired speed
|
||||
|
Loading…
Reference in New Issue
Block a user