ardupilot/APMrover2/sensors.pde

119 lines
4.0 KiB
Plaintext
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static void init_sonar(void)
{
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
sonar.Init(&adc);
2013-03-21 18:49:51 -03:00
sonar2.Init(&adc);
#else
sonar.Init(NULL);
2013-03-21 18:49:51 -03:00
sonar2.Init(NULL);
#endif
}
/*
read and update the battery
*/
static void read_battery(void)
{
if(g.battery_monitoring == 0) {
battery_voltage1 = 0;
return;
}
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);
}
if (g.battery_monitoring == 4) {
static uint32_t last_time_ms;
uint32_t tnow = hal.scheduler->millis();
float dt = tnow - last_time_ms;
if (last_time_ms != 0 && dt < 2000) {
// this copes with changing the pin at runtime
batt_curr_pin->set_pin(g.battery_curr_pin);
current_amps1 = CURRENT_AMPS(batt_curr_pin);
// .0002778 is 1/3600 (conversion to hours)
2013-06-04 00:34:09 -03:00
current_total1 += current_amps1 * dt * 0.0002778f;
}
last_time_ms = tnow;
}
}
// 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->voltage_average() * 50;
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
obstacle.sonar1_distance_cm = sonar.distance_cm();
obstacle.sonar2_distance_cm = sonar2.distance_cm();
2013-04-19 18:29:57 -03:00
if (obstacle.sonar1_distance_cm <= (uint16_t)g.sonar_trigger_cm &&
obstacle.sonar2_distance_cm <= (uint16_t)obstacle.sonar2_distance_cm) {
2013-03-21 18:49:51 -03:00
// we have an object on the left
if (obstacle.detected_count < 127) {
obstacle.detected_count++;
}
if (obstacle.detected_count == g.sonar_debounce) {
2013-05-28 20:59:21 -03:00
gcs_send_text_fmt(PSTR("Sonar1 obstacle %u cm"),
(unsigned)obstacle.sonar1_distance_cm);
2013-03-28 18:53:02 -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-04-19 18:29:57 -03:00
} else if (obstacle.sonar2_distance_cm <= (uint16_t)g.sonar_trigger_cm) {
2013-03-21 18:49:51 -03:00
// we have an object on the right
if (obstacle.detected_count < 127) {
obstacle.detected_count++;
}
if (obstacle.detected_count == g.sonar_debounce) {
2013-05-28 20:59:21 -03:00
gcs_send_text_fmt(PSTR("Sonar2 obstacle %u cm"),
(unsigned)obstacle.sonar2_distance_cm);
2013-03-28 18:53:02 -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 {
// we have a single sonar
obstacle.sonar1_distance_cm = sonar.distance_cm();
obstacle.sonar2_distance_cm = 0;
2013-04-19 18:29:57 -03:00
if (obstacle.sonar1_distance_cm <= (uint16_t)g.sonar_trigger_cm) {
// obstacle detected in front
if (obstacle.detected_count < 127) {
obstacle.detected_count++;
}
if (obstacle.detected_count == g.sonar_debounce) {
2013-05-28 20:59:21 -03:00
gcs_send_text_fmt(PSTR("Sonar obstacle %u cm"),
(unsigned)obstacle.sonar1_distance_cm);
2013-03-28 18:53:02 -03:00
}
obstacle.detected_time_ms = hal.scheduler->millis();
obstacle.turn_angle = g.sonar_turn_angle;
}
2013-03-21 18:49:51 -03:00
}
Log_Write_Sonar();
2013-03-21 18:49:51 -03:00
// no object detected - reset after the turn time
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"));
obstacle.detected_count = 0;
obstacle.turn_angle = 0;
2013-03-21 18:49:51 -03:00
}
}