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_MicroStrain5.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.5This program is distributed in the hope that it will be useful,6but WITHOUT ANY WARRANTY; without even the implied warranty of7MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the8GNU General Public License for more details.9You should have received a copy of the GNU General Public License10along with this program. If not, see <http://www.gnu.org/licenses/>.11*/12/*13support for MicroStrain CX5/GX5-45 serially connected AHRS Systems14*/1516#define ALLOW_DOUBLE_MATH_FUNCTIONS1718#include "AP_ExternalAHRS_config.h"1920#if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED2122#include "AP_ExternalAHRS_MicroStrain5.h"23#include "AP_Compass/AP_Compass_config.h"24#include <AP_Baro/AP_Baro.h>25#include <AP_Compass/AP_Compass.h>26#include <AP_GPS/AP_GPS.h>27#include <AP_HAL/utility/sparse-endian.h>28#include <AP_InertialSensor/AP_InertialSensor.h>29#include <GCS_MAVLink/GCS.h>30#include <AP_Logger/AP_Logger.h>31#include <AP_BoardConfig/AP_BoardConfig.h>32#include <AP_SerialManager/AP_SerialManager.h>3334extern const AP_HAL::HAL &hal;3536static constexpr uint8_t gnss_instance = 0;3738AP_ExternalAHRS_MicroStrain5::AP_ExternalAHRS_MicroStrain5(AP_ExternalAHRS *_frontend,39AP_ExternalAHRS::state_t &_state): AP_ExternalAHRS_backend(_frontend, _state)40{41auto &sm = AP::serialmanager();42uart = sm.find_serial(AP_SerialManager::SerialProtocol_AHRS, 0);4344baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0);45port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0);4647if (!uart) {48GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "MicroStrain5 ExternalAHRS no UART");49return;50}5152if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_MicroStrain5::update_thread, void), "AHRS", 2048, AP_HAL::Scheduler::PRIORITY_SPI, 0)) {53AP_BoardConfig::allocation_error("MicroStrain5 failed to allocate ExternalAHRS update thread");54}5556hal.scheduler->delay(5000);57GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MicroStrain5 ExternalAHRS initialised");58}5960void AP_ExternalAHRS_MicroStrain5::update_thread(void)61{62if (!port_open) {63port_open = true;64uart->begin(baudrate);65}6667while (true) {68build_packet();69hal.scheduler->delay_microseconds(100);70}71}72737475// Builds packets by looking at each individual byte, once a full packet has been read in it checks the checksum then handles the packet.76void AP_ExternalAHRS_MicroStrain5::build_packet()77{78if (uart == nullptr) {79return;80}8182WITH_SEMAPHORE(sem);83uint32_t nbytes = MIN(uart->available(), 2048u);84while (nbytes--> 0) {85uint8_t b;86if (!uart->read(b)) {87break;88}89DescriptorSet descriptor;90if (handle_byte(b, descriptor)) {91switch (descriptor) {92case DescriptorSet::IMUData:93post_imu();94break;95case DescriptorSet::GNSSData:96case DescriptorSet::GNSSRecv1:97case DescriptorSet::GNSSRecv2:98break;99case DescriptorSet::FilterData:100post_filter();101break;102case DescriptorSet::BaseCommand:103case DescriptorSet::DMCommand:104case DescriptorSet::SystemCommand:105break;106}107}108}109}110111112113// Posts data from an imu packet to `state` and `handle_external` methods114void AP_ExternalAHRS_MicroStrain5::post_imu() const115{116{117WITH_SEMAPHORE(state.sem);118state.accel = imu_data.accel;119state.gyro = imu_data.gyro;120121state.quat = imu_data.quat;122state.have_quaternion = true;123}124125{126AP_ExternalAHRS::ins_data_message_t ins {127accel: imu_data.accel,128gyro: imu_data.gyro,129temperature: -300130};131AP::ins().handle_external(ins);132}133134#if AP_COMPASS_EXTERNALAHRS_ENABLED135{136AP_ExternalAHRS::mag_data_message_t mag {137field: imu_data.mag138};139AP::compass().handle_external(mag);140}141#endif142143#if AP_BARO_EXTERNALAHRS_ENABLED144{145const AP_ExternalAHRS::baro_data_message_t baro {146instance: 0,147pressure_pa: imu_data.pressure,148// setting temp to 25 effectively disables barometer temperature calibrations - these are already performed by MicroStrain149temperature: 25,150};151AP::baro().handle_external(baro);152}153#endif154}155156void AP_ExternalAHRS_MicroStrain5::post_filter() const157{158{159WITH_SEMAPHORE(state.sem);160state.velocity = Vector3f{filter_data.ned_velocity_north, filter_data.ned_velocity_east, filter_data.ned_velocity_down};161state.have_velocity = true;162163state.location = Location{filter_data.lat, filter_data.lon, gnss_data[gnss_instance].msl_altitude, Location::AltFrame::ABSOLUTE};164state.have_location = true;165state.last_location_update_us = AP_HAL::micros();166}167168AP_ExternalAHRS::gps_data_message_t gps {169gps_week: filter_data.week,170ms_tow: filter_data.tow_ms,171fix_type: AP_GPS_FixType(gnss_data[gnss_instance].fix_type),172satellites_in_view: gnss_data[gnss_instance].satellites,173174horizontal_pos_accuracy: gnss_data[gnss_instance].horizontal_position_accuracy,175vertical_pos_accuracy: gnss_data[gnss_instance].vertical_position_accuracy,176horizontal_vel_accuracy: gnss_data[gnss_instance].speed_accuracy,177178hdop: gnss_data[gnss_instance].hdop,179vdop: gnss_data[gnss_instance].vdop,180181longitude: filter_data.lon,182latitude: filter_data.lat,183msl_altitude: gnss_data[gnss_instance].msl_altitude,184185ned_vel_north: filter_data.ned_velocity_north,186ned_vel_east: filter_data.ned_velocity_east,187ned_vel_down: filter_data.ned_velocity_down,188};189190if (gps.fix_type >= AP_GPS_FixType::FIX_3D && !state.have_origin) {191WITH_SEMAPHORE(state.sem);192state.origin = Location{int32_t(filter_data.lat),193int32_t(filter_data.lon),194int32_t(gnss_data[gnss_instance].msl_altitude),195Location::AltFrame::ABSOLUTE};196state.have_origin = true;197}198199uint8_t gps_instance;200if (AP::gps().get_first_external_instance(gps_instance)) {201AP::gps().handle_external(gps, gps_instance);202}203}204205int8_t AP_ExternalAHRS_MicroStrain5::get_port(void) const206{207if (!uart) {208return -1;209}210return port_num;211};212213// Get model/type name214const char* AP_ExternalAHRS_MicroStrain5::get_name() const215{216return "MicroStrain5";217}218219bool AP_ExternalAHRS_MicroStrain5::healthy(void) const220{221uint32_t now = AP_HAL::millis();222return (now - last_imu_pkt < 40 && now - last_gps_pkt < 500 && now - last_filter_pkt < 500);223}224225bool AP_ExternalAHRS_MicroStrain5::initialised(void) const226{227return last_imu_pkt != 0 && last_gps_pkt != 0 && last_filter_pkt != 0;228}229230bool AP_ExternalAHRS_MicroStrain5::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const231{232if (!healthy()) {233hal.util->snprintf(failure_msg, failure_msg_len, "MicroStrain5 unhealthy");234return false;235}236if (gnss_data[gnss_instance].fix_type < 3) {237hal.util->snprintf(failure_msg, failure_msg_len, "MicroStrain5 no GPS lock");238return false;239}240if (filter_status.state != 0x02) {241hal.util->snprintf(failure_msg, failure_msg_len, "MicroStrain5 filter not running");242return false;243}244245return true;246}247248void AP_ExternalAHRS_MicroStrain5::get_filter_status(nav_filter_status &status) const249{250memset(&status, 0, sizeof(status));251if (last_imu_pkt != 0 && last_gps_pkt != 0) {252status.flags.initalized = true;253}254if (healthy() && last_imu_pkt != 0) {255status.flags.attitude = true;256status.flags.vert_vel = true;257status.flags.vert_pos = true;258259if (gnss_data[gnss_instance].fix_type >= 3) {260status.flags.horiz_vel = true;261status.flags.horiz_pos_rel = true;262status.flags.horiz_pos_abs = true;263status.flags.pred_horiz_pos_rel = true;264status.flags.pred_horiz_pos_abs = true;265status.flags.using_gps = true;266}267}268}269270// get variances271bool AP_ExternalAHRS_MicroStrain5::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const272{273velVar = gnss_data[gnss_instance].speed_accuracy * vel_gate_scale;274posVar = gnss_data[gnss_instance].horizontal_position_accuracy * pos_gate_scale;275hgtVar = gnss_data[gnss_instance].vertical_position_accuracy * hgt_gate_scale;276tasVar = 0;277return true;278}279280281#endif // AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED282283284