mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 23:18:28 -04:00
Rover: fixed coverity issue around loiter logic
This commit is contained in:
parent
41fd596c06
commit
5575eeddab
@ -31,8 +31,11 @@ void ModeGuided::update()
|
|||||||
calc_steering_to_waypoint(_reached_destination ? rover.current_loc : _origin, _destination, _reversed);
|
calc_steering_to_waypoint(_reached_destination ? rover.current_loc : _origin, _destination, _reversed);
|
||||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_reversed ? -_desired_speed : _desired_speed), true, true);
|
calc_throttle(calc_reduced_speed_for_turn_or_distance(_reversed ? -_desired_speed : _desired_speed), true, true);
|
||||||
} else {
|
} else {
|
||||||
if (rover.is_boat() && !start_loiter()) {
|
// we have reached the destination so stay here
|
||||||
stop_vehicle();
|
if (rover.is_boat()) {
|
||||||
|
if (!start_loiter()) {
|
||||||
|
stop_vehicle();
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
stop_vehicle();
|
stop_vehicle();
|
||||||
}
|
}
|
||||||
@ -52,8 +55,11 @@ void ModeGuided::update()
|
|||||||
calc_steering_to_heading(_desired_yaw_cd);
|
calc_steering_to_heading(_desired_yaw_cd);
|
||||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_desired_speed), true, true);
|
calc_throttle(calc_reduced_speed_for_turn_or_distance(_desired_speed), true, true);
|
||||||
} else {
|
} else {
|
||||||
if (rover.is_boat() && !start_loiter()) {
|
// we have reached the destination so stay here
|
||||||
stop_vehicle();
|
if (rover.is_boat()) {
|
||||||
|
if (!start_loiter()) {
|
||||||
|
stop_vehicle();
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
stop_vehicle();
|
stop_vehicle();
|
||||||
}
|
}
|
||||||
@ -77,8 +83,11 @@ void ModeGuided::update()
|
|||||||
g2.motors.set_steering(steering_out * 4500.0f);
|
g2.motors.set_steering(steering_out * 4500.0f);
|
||||||
calc_throttle(_desired_speed, true, true);
|
calc_throttle(_desired_speed, true, true);
|
||||||
} else {
|
} else {
|
||||||
if (rover.is_boat() && !start_loiter()) {
|
// we have reached the destination so stay here
|
||||||
stop_vehicle();
|
if (rover.is_boat()) {
|
||||||
|
if (!start_loiter()) {
|
||||||
|
stop_vehicle();
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
stop_vehicle();
|
stop_vehicle();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user