ardupilot/ArduSub/sensors.cpp

210 lines
5.7 KiB
C++
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2016-01-14 15:30:56 -04:00
#include "Sub.h"
2016-01-14 15:30:56 -04:00
void Sub::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
2016-01-14 15:30:56 -04:00
void Sub::read_barometer(void)
{
barometer.update();
if (should_log(MASK_LOG_IMU)) {
Log_Write_Baro();
}
baro_alt = barometer.get_altitude() * 100.0f;
baro_climbrate = barometer.get_climb_rate() * 100.0f;
motors.set_air_density_ratio(barometer.get_air_density_ratio());
}
void Sub::init_rangefinder(void)
{
#if RANGEFINDER_ENABLED == ENABLED
rangefinder.init();
rangefinder_state.alt_cm_filt.set_cutoff_frequency(RANGEFINDER_WPNAV_FILT_HZ);
rangefinder_state.enabled = (rangefinder.num_sensors() >= 1);
#endif
}
// return rangefinder altitude in centimeters
void Sub::read_rangefinder(void)
{
#if RANGEFINDER_ENABLED == ENABLED
rangefinder.update();
rangefinder_state.alt_healthy = ((rangefinder.status() == RangeFinder::RangeFinder_Good) && (rangefinder.range_valid_count() >= RANGEFINDER_HEALTH_MAX));
int16_t temp_alt = rangefinder.distance_cm();
#if RANGEFINDER_TILT_CORRECTION == ENABLED
// correct alt for angle of the rangefinder
temp_alt = (float)temp_alt * MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z);
#endif
rangefinder_state.alt_cm = temp_alt;
// filter rangefinder for use by AC_WPNav
uint32_t now = AP_HAL::millis();
if (rangefinder_state.alt_healthy) {
if (now - rangefinder_state.last_healthy_ms > RANGEFINDER_TIMEOUT_MS) {
// reset filter if we haven't used it within the last second
rangefinder_state.alt_cm_filt.reset(rangefinder_state.alt_cm);
} else {
rangefinder_state.alt_cm_filt.apply(rangefinder_state.alt_cm, 0.05f);
}
rangefinder_state.last_healthy_ms = now;
}
// send rangefinder altitude and health to waypoint navigation library
wp_nav.set_rangefinder_alt(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
#else
rangefinder_state.enabled = false;
rangefinder_state.alt_healthy = false;
rangefinder_state.alt_cm = 0;
#endif
}
// return true if rangefinder_alt can be used
bool Sub::rangefinder_alt_ok()
{
return (rangefinder_state.enabled && rangefinder_state.alt_healthy);
}
/*
update RPM sensors
*/
2016-01-14 15:30:56 -04:00
void Sub::rpm_update(void)
{
rpm_sensor.update();
if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) {
if (should_log(MASK_LOG_RCIN)) {
DataFlash.Log_Write_RPM(rpm_sensor);
}
}
}
// initialise compass
2016-01-14 15:30:56 -04:00
void Sub::init_compass()
{
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
2016-01-14 15:30:56 -04:00
void Sub::init_optflow()
{
#if OPTFLOW == ENABLED
// exit immediately if not enabled
if (!optflow.enabled()) {
return;
}
// initialise optical flow sensor
optflow.init();
#endif // OPTFLOW == ENABLED
}
// called at 200hz
#if OPTFLOW == ENABLED
2016-01-14 15:30:56 -04:00
void Sub::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();
const Vector3f &posOffset = optflow.get_pos_offset();
ahrs.writeOptFlowMeas(flowQuality, flowRate, bodyRate, last_of_update, posOffset);
if (g.log_bitmask & MASK_LOG_OPTFLOW) {
Log_Write_Optflow();
}
}
}
#endif // OPTFLOW == ENABLED
// read_battery - check battery voltage and current and invoke failsafe if necessary
// called at 10hz
2016-01-14 15:30:56 -04:00
void Sub::read_battery(void)
{
battery.read();
// update compass with current value
if (battery.has_current()) {
compass.set_current(battery.current_amps());
}
// 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());
}
// 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();
}
// log battery info to the dataflash
if (should_log(MASK_LOG_CURRENT)) {
Log_Write_Current();
}
}
2016-01-14 15:30:56 -04:00
void Sub::compass_cal_update()
{
if (!hal.util->get_soft_armed()) {
compass.compass_cal_update();
}
}
2016-01-14 15:30:56 -04:00
void Sub::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));
}
}
#if GRIPPER_ENABLED == ENABLED
// gripper update
void Sub::gripper_update()
{
g2.gripper.update();
}
#endif