2011-03-19 07:20:11 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
#if CONFIG_SONAR == ENABLED
|
2011-12-11 03:40:59 -04:00
|
|
|
static void init_sonar(void)
|
|
|
|
{
|
2014-06-27 01:23:56 -03:00
|
|
|
sonar.init();
|
2011-12-11 03:40:59 -04:00
|
|
|
}
|
2014-06-27 01:23:56 -03:00
|
|
|
#endif
|
2011-12-11 03:40:59 -04:00
|
|
|
|
2014-01-15 10:18:23 -04:00
|
|
|
static void init_barometer(bool full_calibration)
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2013-05-25 00:21:29 -03:00
|
|
|
gcs_send_text_P(SEVERITY_LOW, PSTR("Calibrating barometer"));
|
2014-01-15 10:18:23 -04:00
|
|
|
if (full_calibration) {
|
|
|
|
barometer.calibrate();
|
|
|
|
}else{
|
|
|
|
barometer.update_calibration();
|
|
|
|
}
|
2012-06-20 02:17:15 -03:00
|
|
|
gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete"));
|
2011-02-25 01:33:39 -04:00
|
|
|
}
|
2011-12-26 19:13:47 -04:00
|
|
|
|
2012-06-20 02:17:15 -03:00
|
|
|
// return barometric altitude in centimeters
|
2011-11-07 18:24:32 -04:00
|
|
|
static int32_t read_barometer(void)
|
2011-02-21 00:30:56 -04:00
|
|
|
{
|
2012-08-16 21:50:03 -03:00
|
|
|
barometer.read();
|
2014-02-18 16:38:20 -04:00
|
|
|
if (g.log_bitmask & MASK_LOG_IMU) {
|
|
|
|
Log_Write_Baro();
|
|
|
|
}
|
2014-07-28 05:38:32 -03:00
|
|
|
int32_t balt = barometer.get_altitude() * 100.0f;
|
|
|
|
|
|
|
|
// run glitch protection and update AP_Notify if home has been initialised
|
|
|
|
baro_glitch.check_alt();
|
|
|
|
bool report_baro_glitch = (baro_glitch.glitching() && !ap.usb_connected && hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
|
|
|
|
if (AP_Notify::flags.baro_glitching != report_baro_glitch) {
|
|
|
|
if (baro_glitch.glitching()) {
|
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_BARO, ERROR_CODE_BARO_GLITCH);
|
|
|
|
} else {
|
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_GPS, ERROR_CODE_ERROR_RESOLVED);
|
|
|
|
}
|
|
|
|
AP_Notify::flags.baro_glitching = report_baro_glitch;
|
|
|
|
}
|
|
|
|
|
|
|
|
// return altitude
|
|
|
|
return balt;
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
|
2012-12-21 01:03:47 -04:00
|
|
|
// return sonar altitude in centimeters
|
|
|
|
static int16_t read_sonar(void)
|
|
|
|
{
|
|
|
|
#if CONFIG_SONAR == ENABLED
|
2014-06-27 01:23:56 -03:00
|
|
|
sonar.update();
|
|
|
|
|
2013-01-31 04:00:28 -04:00
|
|
|
// exit immediately if sonar is disabled
|
2014-06-27 01:23:56 -03:00
|
|
|
if (!sonar_enabled || !sonar.healthy()) {
|
2013-01-31 04:00:28 -04:00
|
|
|
sonar_alt_health = 0;
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
2014-06-27 01:23:56 -03:00
|
|
|
int16_t temp_alt = sonar.distance_cm();
|
2012-12-21 01:03:47 -04:00
|
|
|
|
2014-06-27 01:23:56 -03:00
|
|
|
if (temp_alt >= sonar.min_distance_cm() &&
|
|
|
|
temp_alt <= sonar.max_distance_cm() * SONAR_RELIABLE_DISTANCE_PCT) {
|
2013-01-08 03:41:07 -04:00
|
|
|
if ( sonar_alt_health < SONAR_ALT_HEALTH_MAX ) {
|
|
|
|
sonar_alt_health++;
|
|
|
|
}
|
2012-12-29 00:51:14 -04:00
|
|
|
}else{
|
2013-01-08 03:41:07 -04:00
|
|
|
sonar_alt_health = 0;
|
2012-12-29 00:51:14 -04:00
|
|
|
}
|
|
|
|
|
2012-12-21 01:03:47 -04:00
|
|
|
#if SONAR_TILT_CORRECTION == 1
|
|
|
|
// correct alt for angle of the sonar
|
2014-02-08 03:40:45 -04:00
|
|
|
float temp = ahrs.cos_pitch() * ahrs.cos_roll();
|
2013-01-10 14:42:24 -04:00
|
|
|
temp = max(temp, 0.707f);
|
2012-12-21 01:03:47 -04:00
|
|
|
temp_alt = (float)temp_alt * temp;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
return temp_alt;
|
|
|
|
#else
|
|
|
|
return 0;
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2011-12-29 23:06:31 -04:00
|
|
|
static void init_compass()
|
|
|
|
{
|
2012-08-16 21:50:03 -03:00
|
|
|
if (!compass.init() || !compass.read()) {
|
2012-02-24 23:09:12 -04:00
|
|
|
// make sure we don't pass a broken compass to DCM
|
2012-11-21 02:08:03 -04:00
|
|
|
cliSerial->println_P(PSTR("COMPASS INIT ERROR"));
|
2012-12-29 23:08:25 -04:00
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE);
|
2012-02-24 23:09:12 -04:00
|
|
|
return;
|
|
|
|
}
|
2012-03-11 05:36:12 -03:00
|
|
|
ahrs.set_compass(&compass);
|
2011-12-29 23:06:31 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
static void init_optflow()
|
|
|
|
{
|
2012-11-18 12:16:07 -04:00
|
|
|
#if OPTFLOW == ENABLED
|
2014-01-08 23:29:50 -04:00
|
|
|
optflow.init();
|
|
|
|
if (!optflow.healthy()) {
|
2012-08-16 21:50:03 -03:00
|
|
|
g.optflow_enabled = false;
|
2014-01-08 23:29:50 -04:00
|
|
|
cliSerial->print_P(PSTR("Failed to Init OptFlow\n"));
|
2012-12-29 23:08:25 -04:00
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_OPTFLOW,ERROR_CODE_FAILED_TO_INITIALISE);
|
2012-12-10 11:14:29 -04:00
|
|
|
}
|
2012-11-18 12:16:07 -04:00
|
|
|
#endif // OPTFLOW == ENABLED
|
2011-12-29 23:06:31 -04:00
|
|
|
}
|
|
|
|
|
2012-11-13 10:43:54 -04:00
|
|
|
// read_battery - check battery voltage and current and invoke failsafe if necessary
|
|
|
|
// called at 10hz
|
2011-07-17 07:32:00 -03:00
|
|
|
static void read_battery(void)
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2013-10-01 10:34:44 -03:00
|
|
|
battery.read();
|
2011-01-17 22:48:44 -04:00
|
|
|
|
2013-10-01 10:34:44 -03:00
|
|
|
// update compass with current value
|
|
|
|
if (battery.monitoring() == AP_BATT_MONITOR_VOLTAGE_AND_CURRENT) {
|
|
|
|
compass.set_current(battery.current_amps());
|
2012-08-16 21:50:03 -03:00
|
|
|
}
|
|
|
|
|
2012-11-13 10:43:54 -04:00
|
|
|
// check for low voltage or current if the low voltage check hasn't already been triggered
|
2013-09-12 10:41:28 -03:00
|
|
|
// we only check when we're not powered by USB to avoid false alarms during bench tests
|
2013-10-13 01:52:52 -03:00
|
|
|
if (!ap.usb_connected && !failsafe.battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
|
|
|
|
failsafe_battery_event();
|
2012-08-16 21:50:03 -03:00
|
|
|
}
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
2012-11-22 05:59:33 -04:00
|
|
|
|
|
|
|
// read the receiver RSSI as an 8 bit number for MAVLink
|
|
|
|
// RC_CHANNELS_SCALED message
|
|
|
|
void read_receiver_rssi(void)
|
|
|
|
{
|
2013-11-15 19:17:31 -04:00
|
|
|
// avoid divide by zero
|
|
|
|
if (g.rssi_range <= 0) {
|
|
|
|
receiver_rssi = 0;
|
|
|
|
}else{
|
|
|
|
rssi_analog_source->set_pin(g.rssi_pin);
|
|
|
|
float ret = rssi_analog_source->voltage_average() * 255 / g.rssi_range;
|
|
|
|
receiver_rssi = constrain_int16(ret, 0, 255);
|
|
|
|
}
|
2012-11-22 05:59:33 -04:00
|
|
|
}
|