Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduSub/sensors.cpp
Views: 1798
#include "Sub.h"12// return barometric altitude in centimeters3void Sub::read_barometer()4{5barometer.update();6// If we are reading a positive altitude, the sensor needs calibration7// Even a few meters above the water we should have no significant depth reading8if(barometer.get_altitude() > 0) {9barometer.update_calibration();10}1112if (ap.depth_sensor_present) {13sensor_health.depth = barometer.healthy(depth_sensor_idx);14}15}1617void Sub::init_rangefinder()18{19#if AP_RANGEFINDER_ENABLED20rangefinder.set_log_rfnd_bit(MASK_LOG_CTUN);21rangefinder.init(ROTATION_PITCH_270);22rangefinder_state.alt_cm_filt.set_cutoff_frequency(RANGEFINDER_WPNAV_FILT_HZ);23rangefinder_state.enabled = rangefinder.has_orientation(ROTATION_PITCH_270);24#endif25}2627// return rangefinder altitude in centimeters28void Sub::read_rangefinder()29{30#if AP_RANGEFINDER_ENABLED31rangefinder.update();3233// signal quality ranges from 0 (worst) to 100 (perfect), -1 means n/a34int8_t signal_quality_pct = rangefinder.signal_quality_pct_orient(ROTATION_PITCH_270);3536rangefinder_state.alt_healthy =37(rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::Good) &&38(rangefinder.range_valid_count_orient(ROTATION_PITCH_270) >= RANGEFINDER_HEALTH_MAX) &&39(signal_quality_pct == -1 || signal_quality_pct >= g.rangefinder_signal_min);4041int16_t temp_alt = rangefinder.distance_cm_orient(ROTATION_PITCH_270);4243#if RANGEFINDER_TILT_CORRECTION44// correct alt for angle of the rangefinder45temp_alt = (float)temp_alt * MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z);46#endif4748rangefinder_state.alt_cm = temp_alt;49rangefinder_state.inertial_alt_cm = inertial_nav.get_position_z_up_cm();50rangefinder_state.min_cm = rangefinder.min_distance_cm_orient(ROTATION_PITCH_270);51rangefinder_state.max_cm = rangefinder.max_distance_cm_orient(ROTATION_PITCH_270);5253// calculate rangefinder_terrain_offset_cm54if (rangefinder_state.alt_healthy) {55uint32_t now = AP_HAL::millis();56if (now - rangefinder_state.last_healthy_ms > RANGEFINDER_TIMEOUT_MS) {57// reset filter if we haven't used it within the last second58rangefinder_state.alt_cm_filt.reset(rangefinder_state.alt_cm);59} else {60rangefinder_state.alt_cm_filt.apply(rangefinder_state.alt_cm, 0.05f);61}62rangefinder_state.last_healthy_ms = now;63rangefinder_state.rangefinder_terrain_offset_cm =64sub.rangefinder_state.inertial_alt_cm - sub.rangefinder_state.alt_cm_filt.get();65}6667// send rangefinder altitude and health to waypoint navigation library68wp_nav.set_rangefinder_terrain_offset(69rangefinder_state.enabled,70rangefinder_state.alt_healthy,71rangefinder_state.rangefinder_terrain_offset_cm);72circle_nav.set_rangefinder_terrain_offset(73rangefinder_state.enabled && wp_nav.rangefinder_used(),74rangefinder_state.alt_healthy,75rangefinder_state.rangefinder_terrain_offset_cm);76#else77rangefinder_state.enabled = false;78rangefinder_state.alt_healthy = false;79rangefinder_state.alt_cm = 0;80rangefinder_state.inertial_alt_cm = 0;81rangefinder_state.rangefinder_terrain_offset_cm = 0;82#endif83}8485// return true if rangefinder_alt can be used86bool Sub::rangefinder_alt_ok() const87{88uint32_t now = AP_HAL::millis();89return (rangefinder_state.enabled && rangefinder_state.alt_healthy && now - rangefinder_state.last_healthy_ms < RANGEFINDER_TIMEOUT_MS);90}919293