mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
Rover: fix calls to calc_steering_to_heading
reversed flag was being passed into the wrong argument
This commit is contained in:
parent
cd64ce45ac
commit
743de16c07
@ -65,7 +65,7 @@ void ModeAuto::update()
|
||||
{
|
||||
if (!_reached_heading) {
|
||||
// run steering and throttle controllers
|
||||
calc_steering_to_heading(_desired_yaw_cd, _desired_speed < 0);
|
||||
calc_steering_to_heading(_desired_yaw_cd);
|
||||
calc_throttle(_desired_speed, true, false);
|
||||
// check if we have reached within 5 degrees of target
|
||||
_reached_heading = (fabsf(_desired_yaw_cd - ahrs.yaw_sensor) < 500);
|
||||
|
@ -68,6 +68,6 @@ void ModeFollow::update()
|
||||
_desired_yaw_cd = wrap_180_cd(atan2f(desired_velocity_ne.y, desired_velocity_ne.x) * DEGX100);
|
||||
|
||||
// run steering and throttle controllers
|
||||
calc_steering_to_heading(_desired_yaw_cd, desired_speed < 0);
|
||||
calc_steering_to_heading(_desired_yaw_cd);
|
||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(desired_speed), false, true);
|
||||
}
|
||||
|
@ -45,7 +45,7 @@ void ModeGuided::update()
|
||||
}
|
||||
if (have_attitude_target) {
|
||||
// run steering and throttle controllers
|
||||
calc_steering_to_heading(_desired_yaw_cd, _desired_speed < 0);
|
||||
calc_steering_to_heading(_desired_yaw_cd);
|
||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_desired_speed), true, true);
|
||||
} else {
|
||||
stop_vehicle();
|
||||
|
@ -49,6 +49,6 @@ void ModeLoiter::update()
|
||||
}
|
||||
|
||||
// run steering and throttle controllers
|
||||
calc_steering_to_heading(_desired_yaw_cd, _desired_speed < 0);
|
||||
calc_steering_to_heading(_desired_yaw_cd);
|
||||
calc_throttle(_desired_speed, false, true);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user