Rover: sonar_trigger_cm of 0 will now only log

This will enable users of Rover to plug their sonar's in (or any other
device into the 3.3v ADC) and log the data but not use the data in
navigation and obstacle avoidance.
This commit is contained in:
Grant Morphett 2016-05-30 13:42:29 +10:00
parent 094d571196
commit a00edcbbb6

View File

@ -67,8 +67,8 @@ void Rover::read_sonars(void)
// we have two sonars
obstacle.sonar1_distance_cm = sonar.distance_cm(0);
obstacle.sonar2_distance_cm = sonar.distance_cm(1);
if (obstacle.sonar1_distance_cm <= (uint16_t)g.sonar_trigger_cm &&
obstacle.sonar1_distance_cm <= (uint16_t)obstacle.sonar2_distance_cm) {
if (obstacle.sonar1_distance_cm < (uint16_t)g.sonar_trigger_cm &&
obstacle.sonar1_distance_cm < (uint16_t)obstacle.sonar2_distance_cm) {
// we have an object on the left
if (obstacle.detected_count < 127) {
obstacle.detected_count++;
@ -79,7 +79,7 @@ void Rover::read_sonars(void)
}
obstacle.detected_time_ms = AP_HAL::millis();
obstacle.turn_angle = g.sonar_turn_angle;
} else if (obstacle.sonar2_distance_cm <= (uint16_t)g.sonar_trigger_cm) {
} else if (obstacle.sonar2_distance_cm < (uint16_t)g.sonar_trigger_cm) {
// we have an object on the right
if (obstacle.detected_count < 127) {
obstacle.detected_count++;
@ -95,7 +95,7 @@ void Rover::read_sonars(void)
// we have a single sonar
obstacle.sonar1_distance_cm = sonar.distance_cm(0);
obstacle.sonar2_distance_cm = 0;
if (obstacle.sonar1_distance_cm <= (uint16_t)g.sonar_trigger_cm) {
if (obstacle.sonar1_distance_cm < (uint16_t)g.sonar_trigger_cm) {
// obstacle detected in front
if (obstacle.detected_count < 127) {
obstacle.detected_count++;