#include "Sub.h" // return barometric altitude in centimeters void Sub::read_barometer() { barometer.update(); if (ap.depth_sensor_present) { sensor_health.depth = barometer.healthy(depth_sensor_idx); } } void Sub::init_rangefinder() { #if RANGEFINDER_ENABLED == ENABLED rangefinder.init(); rangefinder_state.alt_cm_filt.set_cutoff_frequency(RANGEFINDER_WPNAV_FILT_HZ); rangefinder_state.enabled = rangefinder.has_orientation(ROTATION_PITCH_270); #endif } // return rangefinder altitude in centimeters void Sub::read_rangefinder() { #if RANGEFINDER_ENABLED == ENABLED rangefinder.update(); rangefinder_state.alt_healthy = ((rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::RangeFinder_Good) && (rangefinder.range_valid_count_orient(ROTATION_PITCH_270) >= RANGEFINDER_HEALTH_MAX)); int16_t temp_alt = rangefinder.distance_cm_orient(ROTATION_PITCH_270); #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 */ #if RPM_ENABLED == ENABLED void Sub::rpm_update(void) { rpm_sensor.update(); if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) { if (should_log(MASK_LOG_RCIN)) { logger.Write_RPM(rpm_sensor); } } } #endif // initialise compass void Sub::init_compass() { if (!compass.init() || !compass.read()) { // make sure we don't pass a broken compass to DCM hal.console->println("COMPASS INIT ERROR"); Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE); return; } ahrs.set_compass(&compass); } /* initialise compass's location used for declination */ void Sub::init_compass_location() { // update initial location used for declination if (!ap.compass_init_location) { Location loc; if (ahrs.get_position(loc)) { compass.set_initial_location(loc.lat, loc.lng); ap.compass_init_location = true; } } } // initialise optical flow sensor #if OPTFLOW == ENABLED void Sub::init_optflow() { // initialise optical flow sensor optflow.init(MASK_LOG_OPTFLOW); } #endif // OPTFLOW == ENABLED void Sub::compass_cal_update() { if (!hal.util->get_soft_armed()) { compass.compass_cal_update(); } } 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)); } }