ardupilot/ArduCopter/sensors.pde

186 lines
5.3 KiB
Plaintext
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static void init_barometer(bool full_calibration)
{
2013-05-25 00:21:29 -03:00
gcs_send_text_P(SEVERITY_LOW, PSTR("Calibrating barometer"));
if (full_calibration) {
barometer.calibrate();
}else{
barometer.update_calibration();
}
// reset glitch protection to use new baro alt
baro_glitch.reset();
gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete"));
}
// return barometric altitude in centimeters
static void read_barometer(void)
{
2015-01-05 07:28:00 -04:00
barometer.update();
2014-10-16 21:37:49 -03:00
if (should_log(MASK_LOG_IMU)) {
Log_Write_Baro();
}
baro_alt = barometer.get_altitude() * 100.0f;
baro_climbrate = barometer.get_climb_rate() * 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_BARO, ERROR_CODE_ERROR_RESOLVED);
}
AP_Notify::flags.baro_glitching = report_baro_glitch;
}
}
#if CONFIG_SONAR == ENABLED
static void init_sonar(void)
{
sonar.init();
}
#endif
// return sonar altitude in centimeters
static int16_t read_sonar(void)
{
#if CONFIG_SONAR == ENABLED
sonar.update();
// exit immediately if sonar is disabled
if (!sonar_enabled || !sonar.healthy()) {
sonar_alt_health = 0;
return 0;
}
int16_t temp_alt = sonar.distance_cm();
if (temp_alt >= sonar.min_distance_cm() &&
temp_alt <= sonar.max_distance_cm() * SONAR_RELIABLE_DISTANCE_PCT) {
if ( sonar_alt_health < SONAR_ALT_HEALTH_MAX ) {
sonar_alt_health++;
}
}else{
sonar_alt_health = 0;
}
#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();
temp = max(temp, 0.707f);
temp_alt = (float)temp_alt * temp;
#endif
return temp_alt;
#else
return 0;
#endif
}
// initialise compass
static void init_compass()
{
2012-08-16 21:50:03 -03:00
if (!compass.init() || !compass.read()) {
// make sure we don't pass a broken compass to DCM
cliSerial->println_P(PSTR("COMPASS INIT ERROR"));
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE);
return;
}
ahrs.set_compass(&compass);
}
// initialise optical flow sensor
static void init_optflow()
{
#if OPTFLOW == ENABLED
// exit immediately if not enabled
if (!optflow.enabled()) {
return;
}
// initialise sensor and display error on failure
2014-01-08 23:29:50 -04:00
optflow.init();
if (!optflow.healthy()) {
cliSerial->print_P(PSTR("Failed to Init OptFlow\n"));
Log_Write_Error(ERROR_SUBSYSTEM_OPTFLOW,ERROR_CODE_FAILED_TO_INITIALISE);
}
#endif // OPTFLOW == ENABLED
}
// called at 200hz
#if OPTFLOW == ENABLED
static void update_optical_flow(void)
{
static uint32_t last_of_update = 0;
// exit immediately if not enabled
if (!optflow.enabled()) {
return;
}
// read from sensor
optflow.update();
// write to log and send to EKF if new data has arrived
if (optflow.last_update() != last_of_update) {
last_of_update = optflow.last_update();
uint8_t flowQuality = optflow.quality();
Vector2f flowRate = optflow.flowRate();
Vector2f bodyRate = optflow.bodyRate();
// Use range from a separate range finder if available, not the PX4Flows built in sensor which is ineffective
float ground_distance_m = 0.01f*float(sonar_alt);
ahrs.writeOptFlowMeas(flowQuality, flowRate, bodyRate, last_of_update, sonar_alt_health, ground_distance_m);
2015-01-05 22:06:44 -04:00
if (g.log_bitmask & MASK_LOG_OPTFLOW) {
Log_Write_Optflow();
}
}
}
#endif // OPTFLOW == ENABLED
2012-11-13 10:43:54 -04:00
// read_battery - check battery voltage and current and invoke failsafe if necessary
// called at 10hz
static void read_battery(void)
{
2013-10-01 10:34:44 -03:00
battery.read();
2013-10-01 10:34:44 -03:00
// update compass with current value
2014-12-03 01:32:44 -04:00
if (battery.has_current()) {
2013-10-01 10:34:44 -03:00
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
// we only check when we're not powered by USB to avoid false alarms during bench tests
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
}
2014-10-07 09:40:48 -03:00
// log battery info to the dataflash
2014-10-16 21:37:49 -03:00
if (should_log(MASK_LOG_CURRENT)) {
2014-10-07 09:40:48 -03:00
Log_Write_Current();
}
}
// read the receiver RSSI as an 8 bit number for MAVLink
// RC_CHANNELS_SCALED message
void read_receiver_rssi(void)
{
// 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);
}
}
2014-09-15 03:52:21 -03:00
#if EPM_ENABLED == ENABLED
// epm update - moves epm pwm output back to neutral after grab or release is completed
void epm_update()
{
epm.update();
}
#endif