ardupilot/APMrover2/sensors.cpp

118 lines
3.8 KiB
C++
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2015-05-13 00:16:45 -03:00
#include "Rover.h"
void Rover::init_barometer(void)
{
gcs_send_text(MAV_SEVERITY_INFO, "Calibrating barometer");
barometer.calibrate();
gcs_send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
}
void Rover::init_sonar(void)
{
sonar.init();
}
2013-10-02 03:07:28 -03:00
// read_battery - reads battery voltage and current and invokes failsafe
// should be called at 10hz
void Rover::read_battery(void)
{
2013-10-02 03:07:28 -03:00
battery.read();
}
// read the receiver RSSI as an 8 bit number for MAVLink
// RC_CHANNELS_SCALED message
2015-05-12 04:00:25 -03:00
void Rover::read_receiver_rssi(void)
{
receiver_rssi = rssi.read_receiver_rssi_uint8();
}
2013-03-21 18:49:51 -03:00
//Calibrate compass
void Rover::compass_cal_update() {
if (!hal.util->get_soft_armed()) {
compass.compass_cal_update();
}
}
// Accel calibration
void Rover::accel_cal_update() {
if (hal.util->get_soft_armed()) {
return;
}
ins.acal_update();
// check if new trim values, and set them float trim_roll, trim_pitch;
float trim_roll,trim_pitch;
if(ins.get_new_trim(trim_roll, trim_pitch)) {
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
}
}
2013-03-21 18:49:51 -03:00
// read the sonars
void Rover::read_sonars(void)
2013-03-21 18:49:51 -03:00
{
sonar.update();
if (sonar.status() == RangeFinder::RangeFinder_NotConnected) {
2013-03-21 18:49:51 -03:00
// this makes it possible to disable sonar at runtime
return;
}
if (sonar.has_data(1)) {
2013-03-21 18:49:51 -03:00
// we have two sonars
obstacle.sonar1_distance_cm = sonar.distance_cm(0);
obstacle.sonar2_distance_cm = sonar.distance_cm(1);
2013-04-19 18:29:57 -03:00
if (obstacle.sonar1_distance_cm <= (uint16_t)g.sonar_trigger_cm &&
2015-03-02 01:53:43 -04:00
obstacle.sonar1_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) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Sonar1 obstacle %u cm",
2013-05-28 20:59:21 -03:00
(unsigned)obstacle.sonar1_distance_cm);
2013-03-28 18:53:02 -03:00
}
obstacle.detected_time_ms = AP_HAL::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) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Sonar2 obstacle %u cm",
2013-05-28 20:59:21 -03:00
(unsigned)obstacle.sonar2_distance_cm);
2013-03-28 18:53:02 -03:00
}
obstacle.detected_time_ms = AP_HAL::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(0);
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) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Sonar obstacle %u cm",
2013-05-28 20:59:21 -03:00
(unsigned)obstacle.sonar1_distance_cm);
2013-03-28 18:53:02 -03:00
}
obstacle.detected_time_ms = AP_HAL::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 &&
AP_HAL::millis() > obstacle.detected_time_ms + g.sonar_turn_time*1000) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Obstacle passed");
obstacle.detected_count = 0;
obstacle.turn_angle = 0;
2013-03-21 18:49:51 -03:00
}
}