2011-09-08 22:29:39 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
#include "Plane.h"
|
|
|
|
|
|
|
|
void Plane::init_barometer(void)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2012-12-03 20:13:33 -04:00
|
|
|
gcs_send_text_P(SEVERITY_LOW, PSTR("Calibrating barometer"));
|
2012-12-04 18:22:21 -04:00
|
|
|
barometer.calibrate();
|
2012-11-18 17:09:44 -04:00
|
|
|
|
2012-06-19 23:26:58 -03:00
|
|
|
gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete"));
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::init_rangefinder(void)
|
2013-10-30 19:23:21 -03:00
|
|
|
{
|
2015-05-13 20:00:11 -03:00
|
|
|
#if RANGEFINDER_ENABLED == ENABLED
|
2014-08-26 08:17:47 -03:00
|
|
|
rangefinder.init();
|
2015-05-13 20:00:11 -03:00
|
|
|
#endif
|
2013-10-30 19:23:21 -03:00
|
|
|
}
|
|
|
|
|
2014-08-26 08:17:47 -03:00
|
|
|
/*
|
|
|
|
read the rangefinder and update height estimate
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::read_rangefinder(void)
|
2013-10-30 19:23:21 -03:00
|
|
|
{
|
2015-05-13 20:00:11 -03:00
|
|
|
#if RANGEFINDER_ENABLED == ENABLED
|
2014-08-26 08:17:47 -03:00
|
|
|
rangefinder.update();
|
|
|
|
|
2014-01-13 22:07:43 -04:00
|
|
|
if (should_log(MASK_LOG_SONAR))
|
2013-10-30 19:23:21 -03:00
|
|
|
Log_Write_Sonar();
|
2014-08-26 22:50:07 -03:00
|
|
|
|
|
|
|
rangefinder_height_update();
|
2015-05-13 20:00:11 -03:00
|
|
|
#endif
|
2013-10-30 19:23:21 -03:00
|
|
|
}
|
|
|
|
|
2013-08-28 09:37:07 -03:00
|
|
|
/*
|
|
|
|
ask airspeed sensor for a new value
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::read_airspeed(void)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2013-06-04 00:34:58 -03:00
|
|
|
if (airspeed.enabled()) {
|
|
|
|
airspeed.read();
|
2014-01-27 19:35:59 -04:00
|
|
|
if (should_log(MASK_LOG_IMU)) {
|
|
|
|
Log_Write_Airspeed();
|
|
|
|
}
|
2013-06-04 00:34:58 -03:00
|
|
|
calc_airspeed_errors();
|
2014-11-11 20:26:49 -04:00
|
|
|
|
|
|
|
// supply a new temperature to the barometer from the digital
|
|
|
|
// airspeed sensor if we can
|
|
|
|
float temperature;
|
|
|
|
if (airspeed.get_temperature(temperature)) {
|
|
|
|
barometer.set_external_temperature(temperature);
|
|
|
|
}
|
2013-06-04 00:34:58 -03:00
|
|
|
}
|
2014-11-11 22:35:34 -04:00
|
|
|
|
|
|
|
// update smoothed airspeed estimate
|
|
|
|
float aspeed;
|
|
|
|
if (ahrs.airspeed_estimate(&aspeed)) {
|
|
|
|
smoothed_airspeed = smoothed_airspeed * 0.8f + aspeed * 0.2f;
|
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::zero_airspeed(bool in_startup)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2014-11-13 06:12:59 -04:00
|
|
|
airspeed.calibrate(in_startup);
|
2014-11-11 20:26:49 -04:00
|
|
|
read_airspeed();
|
|
|
|
// update barometric calibration with new airspeed supplied temperature
|
|
|
|
barometer.update_calibration();
|
2012-08-15 06:49:09 -03:00
|
|
|
gcs_send_text_P(SEVERITY_LOW,PSTR("zero airspeed calibrated"));
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2013-09-29 09:54:39 -03:00
|
|
|
// read_battery - reads battery voltage and current and invokes failsafe
|
|
|
|
// should be called at 10hz
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::read_battery(void)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2013-09-29 09:54:39 -03:00
|
|
|
battery.read();
|
2014-04-14 19:28:32 -03:00
|
|
|
compass.set_current(battery.current_amps());
|
2012-08-16 21:50:15 -03:00
|
|
|
|
2013-09-30 11:15:35 -03:00
|
|
|
if (!usb_connected && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
|
2013-05-22 07:33:57 -03:00
|
|
|
low_battery_event();
|
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2012-08-22 00:33:12 -03:00
|
|
|
|
2012-08-22 00:58:25 -03:00
|
|
|
// read the receiver RSSI as an 8 bit number for MAVLink
|
2012-08-22 00:33:12 -03:00
|
|
|
// RC_CHANNELS_SCALED message
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::read_receiver_rssi(void)
|
2012-08-22 00:33:12 -03:00
|
|
|
{
|
2014-01-29 20:29:35 -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-08-22 00:33:12 -03:00
|
|
|
}
|
2012-09-19 03:22:53 -03:00
|
|
|
|