mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Rover: simplify logic for lateral-accel override during use-pivot-steering
It was theoretically possible that the lateral-acceleration would not be overwritten if the yaw-error-cd was exactly zero
This commit is contained in:
parent
2b0645d6a1
commit
7e2214c2be
@ -205,10 +205,9 @@ void Mode::calc_lateral_acceleration(const struct Location &origin, const struct
|
||||
_yaw_error_cd = wrap_180_cd(rover.nav_controller->target_bearing_cd() - ahrs.yaw_sensor);
|
||||
}
|
||||
if (rover.use_pivot_steering(_yaw_error_cd)) {
|
||||
if (is_positive(_yaw_error_cd)) {
|
||||
if (_yaw_error_cd >= 0.0f) {
|
||||
lateral_acceleration = g.turn_max_g * GRAVITY_MSS;
|
||||
}
|
||||
if (is_negative(_yaw_error_cd)) {
|
||||
} else {
|
||||
lateral_acceleration = -g.turn_max_g * GRAVITY_MSS;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user