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/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15support for serial connected AHRS systems16*/1718#include "AP_ExternalAHRS_config.h"1920#if HAL_EXTERNAL_AHRS_ENABLED2122#include "AP_ExternalAHRS.h"23#include "AP_ExternalAHRS_backend.h"24#include "AP_ExternalAHRS_VectorNav.h"25#include "AP_ExternalAHRS_MicroStrain5.h"26#include "AP_ExternalAHRS_MicroStrain7.h"27#include "AP_ExternalAHRS_InertialLabs.h"2829#include <GCS_MAVLink/GCS.h>30#include <AP_AHRS/AP_AHRS.h>31#include <AP_GPS/AP_GPS.h>32#include <AP_Logger/AP_Logger.h>3334extern const AP_HAL::HAL &hal;3536AP_ExternalAHRS *AP_ExternalAHRS::_singleton;3738// constructor39AP_ExternalAHRS::AP_ExternalAHRS()40{41AP_Param::setup_object_defaults(this, var_info);42_singleton = this;43if (rate.get() < 50) {44// min 50Hz45rate.set(50);46}47}4849#ifndef HAL_EXTERNAL_AHRS_DEFAULT50#define HAL_EXTERNAL_AHRS_DEFAULT 051#endif525354// table of user settable parameters55const AP_Param::GroupInfo AP_ExternalAHRS::var_info[] = {5657// @Param: _TYPE58// @DisplayName: AHRS type59// @Description: Type of AHRS device60// @Values: 0:None,1:VectorNav,2:MicroStrain5,5:InertialLabs,7:MicroStrain761// @User: Standard62AP_GROUPINFO_FLAGS("_TYPE", 1, AP_ExternalAHRS, devtype, HAL_EXTERNAL_AHRS_DEFAULT, AP_PARAM_FLAG_ENABLE),6364// @Param: _RATE65// @DisplayName: AHRS data rate66// @Description: Requested rate for AHRS device67// @Units: Hz68// @User: Standard69AP_GROUPINFO("_RATE", 2, AP_ExternalAHRS, rate, 50),7071// @Param: _OPTIONS72// @DisplayName: External AHRS options73// @Description: External AHRS options bitmask74// @Bitmask: 0:Vector Nav use uncompensated values for accel gyro and mag.75// @User: Standard76AP_GROUPINFO("_OPTIONS", 3, AP_ExternalAHRS, options, 0),7778// @Param: _SENSORS79// @DisplayName: External AHRS sensors80// @Description: External AHRS sensors bitmask81// @Bitmask: 0:GPS,1:IMU,2:Baro,3:Compass82// @User: Advanced83AP_GROUPINFO("_SENSORS", 4, AP_ExternalAHRS, sensors, 0xF),8485// @Param: _LOG_RATE86// @DisplayName: AHRS logging rate87// @Description: Logging rate for EARHS devices88// @Units: Hz89// @User: Standard90AP_GROUPINFO("_LOG_RATE", 5, AP_ExternalAHRS, log_rate, 10),9192AP_GROUPEND93};949596void AP_ExternalAHRS::init(void)97{98if (rate.get() < 50) {99// min 50Hz100rate.set(50);101}102103switch (DevType(devtype)) {104case DevType::None:105// nothing to do106return;107108#if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED109case DevType::VecNav:110backend = NEW_NOTHROW AP_ExternalAHRS_VectorNav(this, state);111return;112#endif113114#if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED115case DevType::MicroStrain5:116backend = NEW_NOTHROW AP_ExternalAHRS_MicroStrain5(this, state);117return;118#endif119120#if AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED121case DevType::MicroStrain7:122backend = NEW_NOTHROW AP_ExternalAHRS_MicroStrain7(this, state);123return;124#endif125126#if AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED127case DevType::InertialLabs:128backend = NEW_NOTHROW AP_ExternalAHRS_InertialLabs(this, state);129return;130#endif131132}133134GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unsupported ExternalAHRS type %u", unsigned(devtype));135}136137bool AP_ExternalAHRS::enabled() const138{139return DevType(devtype) != DevType::None;140}141142// get serial port number for the uart, or -1 if not applicable143int8_t AP_ExternalAHRS::get_port(AvailableSensor sensor) const144{145if (!backend || !has_sensor(sensor)) {146return -1;147}148return backend->get_port();149};150151// accessors for AP_AHRS152bool AP_ExternalAHRS::healthy(void) const153{154return backend && backend->healthy();155}156157bool AP_ExternalAHRS::initialised(void) const158{159return backend && backend->initialised();160}161162bool AP_ExternalAHRS::get_quaternion(Quaternion &quat)163{164if (state.have_quaternion) {165WITH_SEMAPHORE(state.sem);166quat = state.quat;167return true;168}169return false;170}171172bool AP_ExternalAHRS::get_origin(Location &loc)173{174if (state.have_origin) {175WITH_SEMAPHORE(state.sem);176loc = state.origin;177return true;178}179return false;180}181182bool AP_ExternalAHRS::set_origin(const Location &loc)183{184WITH_SEMAPHORE(state.sem);185if (state.have_origin) {186return false;187}188state.origin = loc;189state.have_origin = true;190return true;191}192193bool AP_ExternalAHRS::get_location(Location &loc)194{195if (!state.have_location) {196return false;197}198WITH_SEMAPHORE(state.sem);199loc = state.location;200201if (state.last_location_update_us != 0 &&202state.have_velocity) {203// extrapolate position based on velocity to cope with slow backends204const float dt = (AP_HAL::micros() - state.last_location_update_us)*1.0e-6;205if (dt < 1) {206// only extrapolate for 1s max207Vector3p ofs = state.velocity.topostype();208ofs *= dt;209loc.offset(ofs);210}211}212213return true;214}215216Vector2f AP_ExternalAHRS::get_groundspeed_vector()217{218WITH_SEMAPHORE(state.sem);219Vector2f vec{state.velocity.x, state.velocity.y};220return vec;221}222223bool AP_ExternalAHRS::get_velocity_NED(Vector3f &vel)224{225if (!state.have_velocity) {226return false;227}228WITH_SEMAPHORE(state.sem);229vel = state.velocity;230return true;231}232233bool AP_ExternalAHRS::get_speed_down(float &speedD)234{235if (!state.have_velocity) {236return false;237}238WITH_SEMAPHORE(state.sem);239speedD = state.velocity.z;240return true;241}242243bool AP_ExternalAHRS::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const244{245if (backend == nullptr) {246hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: Invalid backend");247return false;248}249if (!backend->pre_arm_check(failure_msg, failure_msg_len)) {250return false;251}252// Verify the user has configured the GPS to accept EAHRS data.253if (has_sensor(AvailableSensor::GPS)) {254const auto eahrs_gps_sensors = backend->num_gps_sensors();255256const auto &gps = AP::gps();257uint8_t n_configured_eahrs_gps = 0;258for (uint8_t i = 0; i < GPS_MAX_INSTANCES; ++i) {259const auto gps_type = gps.get_type(i);260if (gps_type == AP_GPS::GPS_TYPE_EXTERNAL_AHRS) {261n_configured_eahrs_gps++;262}263}264265// Once AP supports at least 3 GPS's, change to == and remove the second condition.266// At that point, enforce that all GPS's in EAHRS can report to AP_GPS.267if (n_configured_eahrs_gps < 1 && eahrs_gps_sensors >= 1) {268hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: Incorrect number of GPS sensors configured for EAHRS");269return false;270}271}272273if (!state.have_origin) {274hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: No origin");275return false;276}277return true;278}279280/*281get filter status282*/283void AP_ExternalAHRS::get_filter_status(nav_filter_status &status) const284{285status = {};286if (backend) {287backend->get_filter_status(status);288}289}290291/*292get estimated variances, return false if not implemented293*/294bool AP_ExternalAHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const295{296if (backend != nullptr) {297return backend->get_variances(velVar, posVar, hgtVar, magVar, tasVar);298}299return false;300}301302bool AP_ExternalAHRS::get_gyro(Vector3f &gyro)303{304WITH_SEMAPHORE(state.sem);305if (!has_sensor(AvailableSensor::IMU)) {306return false;307}308gyro = state.gyro;309return true;310}311312bool AP_ExternalAHRS::get_accel(Vector3f &accel)313{314WITH_SEMAPHORE(state.sem);315if (!has_sensor(AvailableSensor::IMU)) {316return false;317}318accel = state.accel;319return true;320}321322// send an EKF_STATUS message to GCS323void AP_ExternalAHRS::send_status_report(GCS_MAVLINK &link) const324{325float velVar, posVar, hgtVar, tasVar;326Vector3f magVar;327if (backend == nullptr || !backend->get_variances(velVar, posVar, hgtVar, magVar, tasVar)) {328return;329}330331uint16_t flags = 0;332nav_filter_status filterStatus {};333get_filter_status(filterStatus);334335if (filterStatus.flags.attitude) {336flags |= EKF_ATTITUDE;337}338if (filterStatus.flags.horiz_vel) {339flags |= EKF_VELOCITY_HORIZ;340}341if (filterStatus.flags.vert_vel) {342flags |= EKF_VELOCITY_VERT;343}344if (filterStatus.flags.horiz_pos_rel) {345flags |= EKF_POS_HORIZ_REL;346}347if (filterStatus.flags.horiz_pos_abs) {348flags |= EKF_POS_HORIZ_ABS;349}350if (filterStatus.flags.vert_pos) {351flags |= EKF_POS_VERT_ABS;352}353if (filterStatus.flags.terrain_alt) {354flags |= EKF_POS_VERT_AGL;355}356if (filterStatus.flags.const_pos_mode) {357flags |= EKF_CONST_POS_MODE;358}359if (filterStatus.flags.pred_horiz_pos_rel) {360flags |= EKF_PRED_POS_HORIZ_REL;361}362if (filterStatus.flags.pred_horiz_pos_abs) {363flags |= EKF_PRED_POS_HORIZ_ABS;364}365if (!filterStatus.flags.initalized) {366flags |= EKF_UNINITIALIZED;367}368369const float mag_var = MAX(magVar.x, MAX(magVar.y, magVar.z));370mavlink_msg_ekf_status_report_send(link.get_chan(), flags,371velVar,372posVar,373hgtVar,374mag_var, 0, 0);375}376377void AP_ExternalAHRS::update(void)378{379if (backend) {380backend->update();381}382383WITH_SEMAPHORE(state.sem);384#if HAL_LOGGING_ENABLED385const uint32_t now_ms = AP_HAL::millis();386if (log_rate.get() > 0 && now_ms - last_log_ms >= uint32_t(1000U/log_rate.get())) {387last_log_ms = now_ms;388389// @LoggerMessage: EAHR390// @Description: External AHRS data391// @Field: TimeUS: Time since system startup392// @Field: Roll: euler roll393// @Field: Pitch: euler pitch394// @Field: Yaw: euler yaw395// @Field: VN: velocity north396// @Field: VE: velocity east397// @Field: VD: velocity down398// @Field: Lat: latitude399// @Field: Lon: longitude400// @Field: Alt: altitude AMSL401// @Field: Flg: nav status flags402403float roll, pitch, yaw;404state.quat.to_euler(roll, pitch, yaw);405nav_filter_status filterStatus {};406get_filter_status(filterStatus);407408AP::logger().WriteStreaming("EAHR", "TimeUS,Roll,Pitch,Yaw,VN,VE,VD,Lat,Lon,Alt,Flg",409"sdddnnnDUm-",410"F000000GG0-",411"QffffffLLfI",412AP_HAL::micros64(),413degrees(roll), degrees(pitch), degrees(yaw),414state.velocity.x, state.velocity.y, state.velocity.z,415state.location.lat, state.location.lng, state.location.alt*0.01,416filterStatus.value);417418// @LoggerMessage: EAHV419// @Description: External AHRS variances420// @Field: TimeUS: Time since system startup421// @Field: Vel: velocity variance422// @Field: Pos: position variance423// @Field: Hgt: height variance424// @Field: MagX: magnetic variance, X425// @Field: MagY: magnetic variance, Y426// @Field: MagZ: magnetic variance, Z427// @Field: TAS: true airspeed variance428429float velVar, posVar, hgtVar, tasVar;430Vector3f magVar;431if (backend != nullptr && backend->get_variances(velVar, posVar, hgtVar, magVar, tasVar)) {432AP::logger().WriteStreaming("EAHV", "TimeUS,Vel,Pos,Hgt,MagX,MagY,MagZ,TAS",433"Qfffffff",434AP_HAL::micros64(),435velVar, posVar, hgtVar,436magVar.x, magVar.y, magVar.z,437tasVar);438}439}440#endif // HAL_LOGGING_ENABLED441}442443// Get model/type name444const char* AP_ExternalAHRS::get_name() const445{446if (backend) {447return backend->get_name();448}449return nullptr;450}451452namespace AP {453454AP_ExternalAHRS &externalAHRS()455{456return *AP_ExternalAHRS::get_singleton();457}458459};460461#endif // HAL_EXTERNAL_AHRS_ENABLED462463464465