ardupilot/ArduCopter/sensors.cpp

217 lines
5.3 KiB
C++
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Copter.h"
void Copter::init_barometer(bool full_calibration)
{
gcs_send_text(MAV_SEVERITY_INFO, "Calibrating barometer");
if (full_calibration) {
barometer.calibrate();
}else{
barometer.update_calibration();
}
gcs_send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
}
// return barometric altitude in centimeters
void Copter::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;
2015-04-22 22:19:44 -03:00
motors.set_air_density_ratio(barometer.get_air_density_ratio());
}
#if CONFIG_SONAR == ENABLED
void Copter::init_sonar(void)
{
sonar.init();
}
#endif
// return sonar altitude in centimeters
int16_t Copter::read_sonar(void)
{
#if CONFIG_SONAR == ENABLED
sonar.update();
// exit immediately if sonar is disabled
if (sonar.status() != RangeFinder::RangeFinder_Good) {
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
}
/*
update RPM sensors
*/
void Copter::rpm_update(void)
{
rpm_sensor.update();
if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) {
2015-08-07 07:34:27 -03:00
if (should_log(MASK_LOG_RCIN)) {
DataFlash.Log_Write_RPM(rpm_sensor);
}
}
}
// initialise compass
void Copter::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("COMPASS INIT ERROR");
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE);
return;
}
ahrs.set_compass(&compass);
}
// initialise optical flow sensor
void Copter::init_optflow()
{
#if OPTFLOW == ENABLED
// exit immediately if not enabled
if (!optflow.enabled()) {
return;
}
// initialise optical flow sensor
2014-01-08 23:29:50 -04:00
optflow.init();
#endif // OPTFLOW == ENABLED
}
// called at 200hz
#if OPTFLOW == ENABLED
void Copter::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();
ahrs.writeOptFlowMeas(flowQuality, flowRate, bodyRate, last_of_update);
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
void Copter::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
}
// update motors with voltage and current
if (battery.get_type() != AP_BattMonitor::BattMonitor_TYPE_NONE) {
motors.set_voltage(battery.voltage());
}
if (battery.has_current()) {
motors.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 Copter::read_receiver_rssi(void)
{
receiver_rssi = rssi.read_receiver_rssi_uint8();
}
2014-09-15 03:52:21 -03:00
void Copter::compass_cal_update()
{
if (!hal.util->get_soft_armed()) {
compass.compass_cal_update();
}
2016-01-05 20:23:16 -04:00
#ifdef CAL_ALWAYS_REBOOT
if (compass.compass_cal_requires_reboot()) {
hal.scheduler->delay(1000);
hal.scheduler->reboot(false);
}
#endif
}
2015-10-16 19:05:53 -03:00
void Copter::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;
if(ins.get_new_trim(trim_roll, trim_pitch)) {
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
}
2016-01-05 20:23:16 -04:00
#ifdef CAL_ALWAYS_REBOOT
if (ins.accel_cal_requires_reboot()) {
hal.scheduler->delay(1000);
hal.scheduler->reboot(false);
}
#endif
2015-10-16 19:05:53 -03:00
}
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 Copter::epm_update()
2014-09-15 03:52:21 -03:00
{
epm.update();
}
#endif