mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: fixed sonar reset after the turn time
thanks to Tom for finding this
This commit is contained in:
parent
a25fede6bb
commit
829a000aa5
@ -70,17 +70,15 @@ static void read_sonars(void)
|
||||
obstacle.detected = true;
|
||||
obstacle.turn_angle = -g.sonar_turn_angle;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
// we have a single sonar
|
||||
float sonar_dist_cm = sonar.distance_cm();
|
||||
if (sonar_dist_cm <= g.sonar_trigger_cm) {
|
||||
// obstacle detected in front
|
||||
obstacle.detected = true;
|
||||
obstacle.detected_time_ms = hal.scheduler->millis();
|
||||
obstacle.turn_angle = g.sonar_turn_angle;
|
||||
return;
|
||||
} else {
|
||||
// we have a single sonar
|
||||
float sonar_dist_cm = sonar.distance_cm();
|
||||
if (sonar_dist_cm <= g.sonar_trigger_cm) {
|
||||
// obstacle detected in front
|
||||
obstacle.detected = true;
|
||||
obstacle.detected_time_ms = hal.scheduler->millis();
|
||||
obstacle.turn_angle = g.sonar_turn_angle;
|
||||
}
|
||||
}
|
||||
|
||||
// no object detected - reset after the turn time
|
||||
|
Loading…
Reference in New Issue
Block a user