Browse Source

Rover: added SONAR_DEBOUNCE option

this allows us to debounce the sonar triggering, which will make it
handle noise better
master
Andrew Tridgell 12 years ago
parent
commit
ad7e8bd9c4
  1. 2
      APMrover2/APMrover2.pde
  2. 2
      APMrover2/Parameters.h
  3. 8
      APMrover2/Parameters.pde
  4. 5
      APMrover2/Steering.pde
  5. 23
      APMrover2/sensors.pde

2
APMrover2/APMrover2.pde

@ -372,7 +372,7 @@ static uint32_t last_heartbeat_ms; @@ -372,7 +372,7 @@ static uint32_t last_heartbeat_ms;
// obstacle detection information
static struct {
// have we detected an obstacle?
bool detected;
uint8_t detected_count;
float turn_angle;
// time when we last detected an obstacle, in milliseconds

2
APMrover2/Parameters.h

@ -107,6 +107,7 @@ public: @@ -107,6 +107,7 @@ public:
k_param_sonar_turn_angle,
k_param_sonar_turn_time,
k_param_sonar2, // sonar2 object
k_param_sonar_debounce,
//
// 210: driving modes
@ -213,6 +214,7 @@ public: @@ -213,6 +214,7 @@ public:
AP_Int16 sonar_trigger_cm;
AP_Float sonar_turn_angle;
AP_Float sonar_turn_time;
AP_Int8 sonar_debounce;
// driving modes

8
APMrover2/Parameters.pde

@ -299,6 +299,14 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -299,6 +299,14 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard
GSCALAR(sonar_turn_time, "SONAR_TURN_TIME", 1.0f),
// @Param: SONAR_DEBOUNCE
// @DisplayName: Sonar debounce count
// @Description: The number of 50Hz sonar hits needed to trigger an obstacle avoidance event. If you get a lot of false sonar events then raise this number
// @Range: 1 100
// @Increment: 1
// @User: Standard
GSCALAR(sonar_debounce, "SONAR_DEBOUNCE", 2),
// @Param: MODE_CH
// @DisplayName: Mode channel
// @Description: RC Channel to use for driving mode control

5
APMrover2/Steering.pde

@ -138,9 +138,8 @@ static void calc_nav_steer() @@ -138,9 +138,8 @@ static void calc_nav_steer()
// positive error = right turn
nav_steer = g.pidNavSteer.get_pid(bearing_error_cd, nav_gain_scaler);
if (obstacle.detected) { // obstacle avoidance
nav_steer += obstacle.turn_angle*100;
}
// avoid obstacles, if any
nav_steer += obstacle.turn_angle*100;
g.channel_steer.servo_out = nav_steer;
}

23
APMrover2/sensors.pde

@ -63,20 +63,24 @@ static void read_sonars(void) @@ -63,20 +63,24 @@ static void read_sonars(void)
if (sonar1_dist_cm <= g.sonar_trigger_cm &&
sonar1_dist_cm <= sonar2_dist_cm) {
// we have an object on the left
if (!obstacle.detected) {
if (obstacle.detected_count < 127) {
obstacle.detected_count++;
}
if (obstacle.detected_count == g.sonar_debounce) {
gcs_send_text_fmt(PSTR("Sonar1 obstacle %.0fcm"),
sonar1_dist_cm);
}
obstacle.detected = true;
obstacle.detected_time_ms = hal.scheduler->millis();
obstacle.turn_angle = g.sonar_turn_angle;
} else if (sonar2_dist_cm <= g.sonar_trigger_cm) {
// we have an object on the right
if (!obstacle.detected) {
if (obstacle.detected_count < 127) {
obstacle.detected_count++;
}
if (obstacle.detected_count == g.sonar_debounce) {
gcs_send_text_fmt(PSTR("Sonar2 obstacle %.0fcm"),
sonar2_dist_cm);
}
obstacle.detected = true;
obstacle.detected_time_ms = hal.scheduler->millis();
obstacle.turn_angle = -g.sonar_turn_angle;
}
@ -85,20 +89,23 @@ static void read_sonars(void) @@ -85,20 +89,23 @@ static void read_sonars(void)
float sonar_dist_cm = sonar.distance_cm();
if (sonar_dist_cm <= g.sonar_trigger_cm) {
// obstacle detected in front
if (!obstacle.detected) {
if (obstacle.detected_count < 127) {
obstacle.detected_count++;
}
if (obstacle.detected_count == g.sonar_debounce) {
gcs_send_text_fmt(PSTR("Sonar obstacle %.0fcm"),
sonar_dist_cm);
}
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
if (obstacle.detected &&
if (obstacle.detected_count >= g.sonar_debounce &&
hal.scheduler->millis() > obstacle.detected_time_ms + g.sonar_turn_time*1000) {
gcs_send_text_fmt(PSTR("Obstacle passed"));
obstacle.detected = false;
obstacle.detected_count = 0;
obstacle.turn_angle = 0;
}
}

Loading…
Cancel
Save