2012-04-30 04:17:14 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2013-02-28 21:00:48 -04:00
|
|
|
|
2012-05-14 12:47:08 -03:00
|
|
|
static void init_sonar(void)
|
|
|
|
{
|
2013-02-28 21:00:48 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
|
|
sonar.Init(&adc);
|
2013-03-21 18:49:51 -03:00
|
|
|
sonar2.Init(&adc);
|
2013-02-28 21:00:48 -04:00
|
|
|
#else
|
|
|
|
sonar.Init(NULL);
|
2013-03-21 18:49:51 -03:00
|
|
|
sonar2.Init(NULL);
|
2013-02-28 21:00:48 -04:00
|
|
|
#endif
|
2012-05-14 12:47:08 -03:00
|
|
|
}
|
|
|
|
|
2012-06-13 03:29:32 -03:00
|
|
|
// Sensors are not available in HIL_MODE_ATTITUDE
|
|
|
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
|
|
|
|
|
|
void ReadSCP1000(void) {}
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
|
|
|
|
|
|
|
static void read_battery(void)
|
|
|
|
{
|
|
|
|
if(g.battery_monitoring == 0) {
|
|
|
|
battery_voltage1 = 0;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2012-12-18 07:44:12 -04:00
|
|
|
if(g.battery_monitoring == 3 || g.battery_monitoring == 4) {
|
|
|
|
// this copes with changing the pin at runtime
|
|
|
|
batt_volt_pin->set_pin(g.battery_volt_pin);
|
2013-03-03 01:15:38 -04:00
|
|
|
battery_voltage1 = BATTERY_VOLTAGE(batt_volt_pin);
|
2012-12-18 07:44:12 -04:00
|
|
|
}
|
|
|
|
if(g.battery_monitoring == 4) {
|
|
|
|
// this copes with changing the pin at runtime
|
|
|
|
batt_curr_pin->set_pin(g.battery_curr_pin);
|
2013-03-03 01:15:38 -04:00
|
|
|
current_amps1 = CURRENT_AMPS(batt_curr_pin);
|
2012-12-18 07:44:12 -04:00
|
|
|
current_total1 += current_amps1 * (float)delta_ms_medium_loop * 0.0002778; // .0002778 is 1/3600 (conversion to hours)
|
2012-06-29 08:51:05 -03:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2013-03-14 18:08:35 -03:00
|
|
|
|
|
|
|
// read the receiver RSSI as an 8 bit number for MAVLink
|
|
|
|
// RC_CHANNELS_SCALED message
|
|
|
|
void read_receiver_rssi(void)
|
|
|
|
{
|
|
|
|
rssi_analog_source->set_pin(g.rssi_pin);
|
|
|
|
float ret = rssi_analog_source->read_average();
|
|
|
|
receiver_rssi = constrain_int16(ret, 0, 255);
|
|
|
|
}
|
2013-03-21 18:49:51 -03:00
|
|
|
|
|
|
|
// read the sonars
|
|
|
|
static void read_sonars(void)
|
|
|
|
{
|
|
|
|
if (!sonar.enabled()) {
|
|
|
|
// this makes it possible to disable sonar at runtime
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (sonar2.enabled()) {
|
|
|
|
// we have two sonars
|
|
|
|
float sonar1_dist_cm = sonar.distance_cm();
|
|
|
|
float sonar2_dist_cm = sonar2.distance_cm();
|
|
|
|
if (sonar1_dist_cm <= g.sonar_trigger_cm &&
|
|
|
|
sonar1_dist_cm <= sonar2_dist_cm) {
|
|
|
|
// we have an object on the left
|
2013-03-28 20:49:08 -03:00
|
|
|
if (obstacle.detected_count < 127) {
|
|
|
|
obstacle.detected_count++;
|
|
|
|
}
|
|
|
|
if (obstacle.detected_count == g.sonar_debounce) {
|
2013-03-28 18:53:02 -03:00
|
|
|
gcs_send_text_fmt(PSTR("Sonar1 obstacle %.0fcm"),
|
|
|
|
sonar1_dist_cm);
|
|
|
|
}
|
2013-03-28 19:36:54 -03:00
|
|
|
obstacle.detected_time_ms = hal.scheduler->millis();
|
2013-03-21 18:49:51 -03:00
|
|
|
obstacle.turn_angle = g.sonar_turn_angle;
|
|
|
|
} else if (sonar2_dist_cm <= g.sonar_trigger_cm) {
|
|
|
|
// we have an object on the right
|
2013-03-28 20:49:08 -03:00
|
|
|
if (obstacle.detected_count < 127) {
|
|
|
|
obstacle.detected_count++;
|
|
|
|
}
|
|
|
|
if (obstacle.detected_count == g.sonar_debounce) {
|
2013-03-28 18:53:02 -03:00
|
|
|
gcs_send_text_fmt(PSTR("Sonar2 obstacle %.0fcm"),
|
|
|
|
sonar2_dist_cm);
|
|
|
|
}
|
2013-03-28 19:36:54 -03:00
|
|
|
obstacle.detected_time_ms = hal.scheduler->millis();
|
2013-03-21 18:49:51 -03:00
|
|
|
obstacle.turn_angle = -g.sonar_turn_angle;
|
|
|
|
}
|
2013-03-28 18:08:14 -03:00
|
|
|
} 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
|
2013-03-28 20:49:08 -03:00
|
|
|
if (obstacle.detected_count < 127) {
|
|
|
|
obstacle.detected_count++;
|
|
|
|
}
|
|
|
|
if (obstacle.detected_count == g.sonar_debounce) {
|
2013-03-28 18:53:02 -03:00
|
|
|
gcs_send_text_fmt(PSTR("Sonar obstacle %.0fcm"),
|
|
|
|
sonar_dist_cm);
|
|
|
|
}
|
2013-03-28 18:08:14 -03:00
|
|
|
obstacle.detected_time_ms = hal.scheduler->millis();
|
|
|
|
obstacle.turn_angle = g.sonar_turn_angle;
|
|
|
|
}
|
2013-03-21 18:49:51 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// no object detected - reset after the turn time
|
2013-03-28 20:49:08 -03:00
|
|
|
if (obstacle.detected_count >= g.sonar_debounce &&
|
2013-03-28 18:53:02 -03:00
|
|
|
hal.scheduler->millis() > obstacle.detected_time_ms + g.sonar_turn_time*1000) {
|
|
|
|
gcs_send_text_fmt(PSTR("Obstacle passed"));
|
2013-03-28 20:49:08 -03:00
|
|
|
obstacle.detected_count = 0;
|
|
|
|
obstacle.turn_angle = 0;
|
2013-03-21 18:49:51 -03:00
|
|
|
}
|
|
|
|
}
|