Path: blob/master/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp
9524 views
/*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 AP_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"28#include "AP_ExternalAHRS_SBG.h"2930#include <GCS_MAVLink/GCS.h>31#include <AP_AHRS/AP_AHRS.h>32#include <AP_GPS/AP_GPS.h>33#include <AP_Logger/AP_Logger.h>3435extern const AP_HAL::HAL &hal;3637AP_ExternalAHRS *AP_ExternalAHRS::_singleton;3839// constructor40AP_ExternalAHRS::AP_ExternalAHRS()41{42AP_Param::setup_object_defaults(this, var_info);43_singleton = this;44if (rate.get() < 50) {45// min 50Hz46rate.set(50);47}48}4950#ifndef HAL_EXTERNAL_AHRS_DEFAULT51#define HAL_EXTERNAL_AHRS_DEFAULT 052#endif535455// table of user settable parameters56const AP_Param::GroupInfo AP_ExternalAHRS::var_info[] = {5758// @Param: _TYPE59// @DisplayName: AHRS type60// @Description: Type of AHRS device61// @Values: 0:None,1:VectorNav,2:MicroStrain5,5:InertialLabs,7:MicroStrain7,8:SBG62// @User: Standard63AP_GROUPINFO_FLAGS("_TYPE", 1, AP_ExternalAHRS, devtype, HAL_EXTERNAL_AHRS_DEFAULT, AP_PARAM_FLAG_ENABLE),6465// @Param: _RATE66// @DisplayName: AHRS data rate67// @Description: Requested rate for AHRS device68// @Units: Hz69// @User: Standard70AP_GROUPINFO("_RATE", 2, AP_ExternalAHRS, rate, 50),7172// @Param: _OPTIONS73// @DisplayName: External AHRS options74// @Description: External AHRS options bitmask75// @Bitmask: 0:Vector Nav use uncompensated values for accel gyro and mag.76// @Bitmask: 1:SBG uses EKF as GNSS.77// @User: Standard78AP_GROUPINFO("_OPTIONS", 3, AP_ExternalAHRS, options, 0),7980// @Param: _SENSORS81// @DisplayName: External AHRS sensors82// @Description: External AHRS sensors bitmask83// @Bitmask: 0:GPS,1:IMU,2:Baro,3:Compass84// @User: Advanced85AP_GROUPINFO("_SENSORS", 4, AP_ExternalAHRS, sensors, 0xF),8687// @Param: _LOG_RATE88// @DisplayName: AHRS logging rate89// @Description: Logging rate for EAHRS devices90// @Units: Hz91// @User: Standard92AP_GROUPINFO("_LOG_RATE", 5, AP_ExternalAHRS, log_rate, 10),9394AP_GROUPEND95};969798void AP_ExternalAHRS::init(void)99{100if (rate.get() < 50) {101// min 50Hz102rate.set(50);103}104105switch (DevType(devtype)) {106case DevType::None:107// nothing to do108return;109110#if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED111case DevType::VecNav:112backend = NEW_NOTHROW AP_ExternalAHRS_VectorNav(this, state);113return;114#endif115116#if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED117case DevType::MicroStrain5:118backend = NEW_NOTHROW AP_ExternalAHRS_MicroStrain5(this, state);119return;120#endif121122#if AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED123case DevType::MicroStrain7:124backend = NEW_NOTHROW AP_ExternalAHRS_MicroStrain7(this, state);125return;126#endif127128#if AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED129case DevType::InertialLabs:130backend = NEW_NOTHROW AP_ExternalAHRS_InertialLabs(this, state);131return;132#endif133134#if AP_EXTERNAL_AHRS_SBG_ENABLED135case DevType::SBG:136backend = NEW_NOTHROW AP_ExternalAHRS_SBG(this, state);137return;138#endif // AP_EXTERNAL_AHRS_SBG_ENABLED139140}141142GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unsupported ExternalAHRS type %u", unsigned(devtype));143}144145bool AP_ExternalAHRS::enabled() const146{147return DevType(devtype) != DevType::None;148}149150// get serial port number for the uart, or -1 if not applicable151int8_t AP_ExternalAHRS::get_port(AvailableSensor sensor) const152{153if (!backend || !has_sensor(sensor)) {154return -1;155}156return backend->get_port();157};158159// accessors for AP_AHRS160bool AP_ExternalAHRS::healthy(void) const161{162return backend && backend->healthy();163}164165bool AP_ExternalAHRS::initialised(void) const166{167return backend && backend->initialised();168}169170bool AP_ExternalAHRS::get_quaternion(Quaternion &quat)171{172if (state.have_quaternion) {173WITH_SEMAPHORE(state.sem);174quat = state.quat;175return true;176}177return false;178}179180bool AP_ExternalAHRS::get_origin(Location &loc)181{182if (state.have_origin) {183WITH_SEMAPHORE(state.sem);184#if CONFIG_HAL_BOARD == HAL_BOARD_SITL185if (!state.origin.initialised()) {186AP_HAL::panic("Uninitialized origin in AP_ExternalAHRS.");187}188#endif189loc = state.origin;190return true;191}192return false;193}194195bool AP_ExternalAHRS::set_origin(const Location &loc)196{197WITH_SEMAPHORE(state.sem);198if (state.have_origin) {199return false;200}201state.origin = loc;202state.have_origin = true;203return true;204}205206bool AP_ExternalAHRS::get_location(Location &loc)207{208if (!state.have_location) {209return false;210}211WITH_SEMAPHORE(state.sem);212loc = state.location;213#if CONFIG_HAL_BOARD == HAL_BOARD_SITL214if (!loc.initialised()) {215AP_HAL::panic("Uninitialized location in AP_ExternalAHRS.");216}217#endif218219if (state.last_location_update_us != 0 &&220state.have_velocity) {221// extrapolate position based on velocity to cope with slow backends222const float dt = (AP_HAL::micros() - state.last_location_update_us)*1.0e-6;223if (dt < 1) {224// only extrapolate for 1s max225Vector3p ofs = state.velocity.topostype();226ofs *= dt;227loc.offset(ofs);228}229}230231return true;232}233234Vector2f AP_ExternalAHRS::get_groundspeed_vector()235{236WITH_SEMAPHORE(state.sem);237Vector2f vec{state.velocity.x, state.velocity.y};238return vec;239}240241bool AP_ExternalAHRS::get_velocity_NED(Vector3f &vel)242{243if (!state.have_velocity) {244return false;245}246WITH_SEMAPHORE(state.sem);247vel = state.velocity;248return true;249}250251bool AP_ExternalAHRS::get_speed_down(float &speedD)252{253if (!state.have_velocity) {254return false;255}256WITH_SEMAPHORE(state.sem);257speedD = state.velocity.z;258return true;259}260261bool AP_ExternalAHRS::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const262{263if (backend == nullptr) {264hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: Invalid backend");265return false;266}267if (!backend->pre_arm_check(failure_msg, failure_msg_len)) {268return false;269}270// Verify the user has configured the GPS to accept EAHRS data.271if (has_sensor(AvailableSensor::GPS)) {272const auto eahrs_gps_sensors = backend->num_gps_sensors();273274const auto &gps = AP::gps();275uint8_t n_configured_eahrs_gps = 0;276for (uint8_t i = 0; i < GPS_MAX_INSTANCES; ++i) {277const auto gps_type = gps.get_type(i);278if (gps_type == AP_GPS::GPS_TYPE_EXTERNAL_AHRS) {279n_configured_eahrs_gps++;280}281}282283// Once AP supports at least 3 GPS's, change to == and remove the second condition.284// At that point, enforce that all GPS's in EAHRS can report to AP_GPS.285if (n_configured_eahrs_gps < 1 && eahrs_gps_sensors >= 1) {286hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: Incorrect number of GPS sensors configured for EAHRS");287return false;288}289}290AP_AHRS &ahrs = AP::ahrs();291if (ahrs.configured_ekf_type() == AP_AHRS::EKFType::EXTERNAL) {292// when using EAHRS as the EKF source, we must have a valid position origin293if (!state.have_origin) {294hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: No origin");295return false;296}297}298return true;299}300301/*302get filter status303*/304void AP_ExternalAHRS::get_filter_status(nav_filter_status &status) const305{306status = {};307if (backend) {308backend->get_filter_status(status);309}310}311312/*313get estimated variances, return false if not implemented314*/315bool AP_ExternalAHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const316{317if (backend != nullptr) {318return backend->get_variances(velVar, posVar, hgtVar, magVar, tasVar);319}320return false;321}322323bool AP_ExternalAHRS::get_gyro(Vector3f &gyro)324{325WITH_SEMAPHORE(state.sem);326if (!has_sensor(AvailableSensor::IMU)) {327return false;328}329gyro = state.gyro;330return true;331}332333bool AP_ExternalAHRS::get_accel(Vector3f &accel)334{335WITH_SEMAPHORE(state.sem);336if (!has_sensor(AvailableSensor::IMU)) {337return false;338}339accel = state.accel;340return true;341}342343// send an EKF_STATUS message to GCS344void AP_ExternalAHRS::send_status_report(GCS_MAVLINK &link) const345{346float velVar, posVar, hgtVar, tasVar;347Vector3f magVar;348if (backend == nullptr || !backend->get_variances(velVar, posVar, hgtVar, magVar, tasVar)) {349return;350}351352uint16_t flags = 0;353nav_filter_status filterStatus {};354get_filter_status(filterStatus);355356if (filterStatus.flags.attitude) {357flags |= EKF_ATTITUDE;358}359if (filterStatus.flags.horiz_vel) {360flags |= EKF_VELOCITY_HORIZ;361}362if (filterStatus.flags.vert_vel) {363flags |= EKF_VELOCITY_VERT;364}365if (filterStatus.flags.horiz_pos_rel) {366flags |= EKF_POS_HORIZ_REL;367}368if (filterStatus.flags.horiz_pos_abs) {369flags |= EKF_POS_HORIZ_ABS;370}371if (filterStatus.flags.vert_pos) {372flags |= EKF_POS_VERT_ABS;373}374if (filterStatus.flags.terrain_alt) {375flags |= EKF_POS_VERT_AGL;376}377if (filterStatus.flags.const_pos_mode) {378flags |= EKF_CONST_POS_MODE;379}380if (filterStatus.flags.pred_horiz_pos_rel) {381flags |= EKF_PRED_POS_HORIZ_REL;382}383if (filterStatus.flags.pred_horiz_pos_abs) {384flags |= EKF_PRED_POS_HORIZ_ABS;385}386if (!filterStatus.flags.initalized) {387flags |= EKF_UNINITIALIZED;388}389390const float mag_var = MAX(magVar.x, MAX(magVar.y, magVar.z));391mavlink_msg_ekf_status_report_send(link.get_chan(), flags,392velVar,393posVar,394hgtVar,395mag_var, 0, 0);396}397398void AP_ExternalAHRS::update(void)399{400if (backend) {401backend->update();402}403404WITH_SEMAPHORE(state.sem);405#if HAL_LOGGING_ENABLED406const uint32_t now_ms = AP_HAL::millis();407if (enabled() && log_rate.get() > 0 && now_ms - last_log_ms >= uint32_t(1000U/log_rate.get())) {408last_log_ms = now_ms;409410// @LoggerMessage: EAHR411// @Description: External AHRS data412// @Field: TimeUS: Time since system startup413// @Field: Roll: euler roll414// @Field: Pitch: euler pitch415// @Field: Yaw: euler yaw416// @Field: VN: velocity north417// @Field: VE: velocity east418// @Field: VD: velocity down419// @Field: Lat: latitude420// @Field: Lon: longitude421// @Field: Alt: altitude AMSL422// @Field: Flg: nav status flags423424float roll, pitch, yaw;425state.quat.to_euler(roll, pitch, yaw);426nav_filter_status filterStatus {};427get_filter_status(filterStatus);428429AP::logger().WriteStreaming("EAHR", "TimeUS,Roll,Pitch,Yaw,VN,VE,VD,Lat,Lon,Alt,Flg",430"sdddnnnDUm-",431"F000000GG0-",432"QffffffLLfI",433AP_HAL::micros64(),434degrees(roll), degrees(pitch), degrees(yaw),435state.velocity.x, state.velocity.y, state.velocity.z,436state.location.lat, state.location.lng, state.location.alt*0.01,437filterStatus.value);438439// @LoggerMessage: EAHV440// @Description: External AHRS variances441// @Field: TimeUS: Time since system startup442// @Field: Vel: velocity variance443// @Field: Pos: position variance444// @Field: Hgt: height variance445// @Field: MagX: magnetic variance, X446// @Field: MagY: magnetic variance, Y447// @Field: MagZ: magnetic variance, Z448// @Field: TAS: true airspeed variance449450float velVar, posVar, hgtVar, tasVar;451Vector3f magVar;452if (backend != nullptr && backend->get_variances(velVar, posVar, hgtVar, magVar, tasVar)) {453AP::logger().WriteStreaming("EAHV", "TimeUS,Vel,Pos,Hgt,MagX,MagY,MagZ,TAS",454"Qfffffff",455AP_HAL::micros64(),456velVar, posVar, hgtVar,457magVar.x, magVar.y, magVar.z,458tasVar);459}460}461#endif // HAL_LOGGING_ENABLED462}463464// Get model/type name465const char* AP_ExternalAHRS::get_name() const466{467if (backend) {468return backend->get_name();469}470return nullptr;471}472473namespace AP {474475AP_ExternalAHRS &externalAHRS()476{477return *AP_ExternalAHRS::get_singleton();478}479480};481482#endif // AP_EXTERNAL_AHRS_ENABLED483484485486