Path: blob/master/libraries/AP_AHRS/AP_AHRS_External.cpp
9531 views
#include "AP_AHRS_External.h"12#if AP_AHRS_EXTERNAL_ENABLED34#include <AP_ExternalAHRS/AP_ExternalAHRS.h>5#include <AP_AHRS/AP_AHRS.h>67// true if the AHRS has completed initialisation8bool AP_AHRS_External::initialised(void) const9{10return AP::externalAHRS().initialised();11}1213void AP_AHRS_External::update()14{15AP::externalAHRS().update();16}1718bool AP_AHRS_External::healthy() const {19return AP::externalAHRS().healthy();20}2122void AP_AHRS_External::get_results(AP_AHRS_Backend::Estimates &results)23{24auto &extahrs = AP::externalAHRS();25const AP_InertialSensor &_ins = AP::ins();26if (!extahrs.get_quaternion(results.quaternion)) {27results.attitude_valid = false;28return;29}30results.attitude_valid = true;31results.quaternion.rotation_matrix(results.dcm_matrix);32// note that this is suspect; we are rotating the matrix and33// eulers away from alignment with the quaternion:34results.dcm_matrix = results.dcm_matrix * AP::ahrs().get_rotation_vehicle_body_to_autopilot_body();35results.dcm_matrix.to_euler(&results.roll_rad, &results.pitch_rad, &results.yaw_rad);3637results.gyro_drift.zero();38if (!extahrs.get_gyro(results.gyro_estimate)) {39results.gyro_estimate = _ins.get_gyro();40}4142Vector3f accel;43if (!extahrs.get_accel(accel)) {44accel = _ins.get_accel();45}4647const Vector3f accel_ef = results.dcm_matrix * AP::ahrs().get_rotation_autopilot_body_to_vehicle_body() * accel;48results.accel_ef = accel_ef;4950results.velocity_NED_valid = AP::externalAHRS().get_velocity_NED(results.velocity_NED);51// a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.52// This is different to the vertical velocity from the EKF which is not always consistent with the vertical position due to the various errors that are being corrected for.53results.vert_pos_rate_D_valid = AP::externalAHRS().get_speed_down(results.vert_pos_rate_D);545556results.location_valid = AP::externalAHRS().get_location(results.location);57}5859Vector2f AP_AHRS_External::groundspeed_vector()60{61return AP::externalAHRS().get_groundspeed_vector();62}636465bool AP_AHRS_External::get_relative_position_NED_origin(Vector3p &vec) const66{67auto &extahrs = AP::externalAHRS();68Location loc, orgn;69if (extahrs.get_origin(orgn) &&70extahrs.get_location(loc)) {71const Vector2f diff2d = orgn.get_distance_NE(loc);72vec = Vector3p(diff2d.x, diff2d.y,73-(loc.alt - orgn.alt)*0.01);74return true;75}76return false;77}7879bool AP_AHRS_External::get_relative_position_NE_origin(Vector2p &posNE) const80{81auto &extahrs = AP::externalAHRS();8283Location loc, orgn;84if (!extahrs.get_location(loc) ||85!extahrs.get_origin(orgn)) {86return false;87}88posNE = orgn.get_distance_NE_postype(loc);89return true;90}9192bool AP_AHRS_External::get_relative_position_D_origin(postype_t &posD) const93{94auto &extahrs = AP::externalAHRS();9596Location orgn, loc;97if (!extahrs.get_origin(orgn) ||98!extahrs.get_location(loc)) {99return false;100}101posD = -(loc.alt - orgn.alt)*0.01;102return true;103}104105bool AP_AHRS_External::pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const106{107return AP::externalAHRS().pre_arm_check(failure_msg, failure_msg_len);108}109110bool AP_AHRS_External::get_filter_status(nav_filter_status &status) const111{112AP::externalAHRS().get_filter_status(status);113return true;114}115116void AP_AHRS_External::send_ekf_status_report(GCS_MAVLINK &link) const117{118AP::externalAHRS().send_status_report(link);119}120121bool AP_AHRS_External::get_origin(Location &ret) const122{123return AP::externalAHRS().get_origin(ret);124}125126void AP_AHRS_External::get_control_limits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const127{128// lower gains in VTOL controllers when flying on DCM129ekfGndSpdLimit = 50.0;130ekfNavVelGainScaler = 0.5;131}132133#endif134135136