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_MicroStrain7.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 GQ7 serially connected AHRS Systems14Usage in SITL with hardware for debugging:15$ sim_vehicle.py -v Plane -A "--serial3=uart:/dev/3dm-gq7" --console --map -DG16$ ./Tools/autotest/sim_vehicle.py -v Plane -A "--serial3=uart:/dev/3dm-gq7" -DG17param set AHRS_EKF_TYPE 1118param set EAHRS_TYPE 719param set GPS1_TYPE 2120param set GPS2_TYPE 2121param set SERIAL3_BAUD 11522param set SERIAL3_PROTOCOL 3623UDEV rules for repeatable USB connection:24$ cat /etc/udev/rules.d/99-usb-serial.rules25SUBSYSTEM=="tty", ATTRS{manufacturer}=="Lord Microstrain", SYMLINK+="3dm-gq7"26Usage with simulated MicroStrain7:27./Tools/autotest/sim_vehicle.py -v Plane -A "--serial3=sim:MicroStrain7" --console --map -DG28*/2930#define ALLOW_DOUBLE_MATH_FUNCTIONS3132#include "AP_ExternalAHRS_config.h"3334#if AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED3536#include "AP_ExternalAHRS_MicroStrain7.h"37#include "AP_Compass/AP_Compass_config.h"38#include <AP_Baro/AP_Baro.h>39#include <AP_Compass/AP_Compass.h>40#include <AP_GPS/AP_GPS.h>41#include <AP_HAL/utility/sparse-endian.h>42#include <AP_InertialSensor/AP_InertialSensor.h>43#include <GCS_MAVLink/GCS.h>44#include <AP_Logger/AP_Logger.h>45#include <AP_BoardConfig/AP_BoardConfig.h>46#include <AP_SerialManager/AP_SerialManager.h>4748static const char* LOG_FMT = "%s ExternalAHRS: %s";4950extern const AP_HAL::HAL &hal;5152AP_ExternalAHRS_MicroStrain7::AP_ExternalAHRS_MicroStrain7(AP_ExternalAHRS *_frontend,53AP_ExternalAHRS::state_t &_state): AP_ExternalAHRS_backend(_frontend, _state)54{55auto &sm = AP::serialmanager();56uart = sm.find_serial(AP_SerialManager::SerialProtocol_AHRS, 0);5758baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0);59port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0);6061if (!uart) {62GCS_SEND_TEXT(MAV_SEVERITY_ERROR, LOG_FMT, get_name(), "no UART");63return;64}6566if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_MicroStrain7::update_thread, void), "AHRS", 2048, AP_HAL::Scheduler::PRIORITY_SPI, 0)) {67AP_BoardConfig::allocation_error("MicroStrain7 ExternalAHRS failed to allocate ExternalAHRS update thread");68}6970// don't offer IMU by default, at 100Hz it is too slow for many aircraft71set_default_sensors(uint16_t(AP_ExternalAHRS::AvailableSensor::GPS) |72uint16_t(AP_ExternalAHRS::AvailableSensor::BARO) |73uint16_t(AP_ExternalAHRS::AvailableSensor::COMPASS));7475hal.scheduler->delay(5000);76if (!initialised()) {77GCS_SEND_TEXT(MAV_SEVERITY_WARNING, LOG_FMT, get_name(), "failed to initialise.");78}79}8081void AP_ExternalAHRS_MicroStrain7::update_thread(void)82{83if (!port_open) {84port_open = true;85uart->begin(baudrate);86}8788while (true) {89build_packet();90hal.scheduler->delay_microseconds(100);91check_initialise_state();92}93}9495void AP_ExternalAHRS_MicroStrain7::check_initialise_state(void)96{97const auto new_init_state = initialised();98// Only send the message after fully booted up, otherwise it gets dropped.99if (!last_init_state && new_init_state && AP_HAL::millis() > 5000) {100GCS_SEND_TEXT(MAV_SEVERITY_INFO, LOG_FMT, get_name(), "initialised.");101last_init_state = new_init_state;102}103}104105106// Builds packets by looking at each individual byte, once a full packet has been read in it checks the checksum then handles the packet.107void AP_ExternalAHRS_MicroStrain7::build_packet()108{109if (uart == nullptr) {110return;111}112113WITH_SEMAPHORE(sem);114uint32_t nbytes = MIN(uart->available(), 2048u);115while (nbytes--> 0) {116uint8_t b;117if (!uart->read(b)) {118break;119}120DescriptorSet descriptor;121if (handle_byte(b, descriptor)) {122switch (descriptor) {123case DescriptorSet::IMUData:124post_imu();125break;126case DescriptorSet::GNSSData:127case DescriptorSet::GNSSRecv1:128case DescriptorSet::GNSSRecv2:129break;130case DescriptorSet::FilterData:131post_filter();132break;133case DescriptorSet::BaseCommand:134case DescriptorSet::DMCommand:135case DescriptorSet::SystemCommand:136break;137}138}139}140}141142143144// Posts data from an imu packet to `state` and `handle_external` methods145void AP_ExternalAHRS_MicroStrain7::post_imu() const146{147{148WITH_SEMAPHORE(state.sem);149state.accel = imu_data.accel;150state.gyro = imu_data.gyro;151}152153{154// *INDENT-OFF*155AP_ExternalAHRS::ins_data_message_t ins {156accel: imu_data.accel,157gyro: imu_data.gyro,158temperature: -300159};160// *INDENT-ON*161AP::ins().handle_external(ins);162}163164#if AP_COMPASS_EXTERNALAHRS_ENABLED165{166// *INDENT-OFF*167AP_ExternalAHRS::mag_data_message_t mag {168field: imu_data.mag169};170// *INDENT-ON*171AP::compass().handle_external(mag);172}173#endif174175#if AP_BARO_EXTERNALAHRS_ENABLED176{177// *INDENT-OFF*178const AP_ExternalAHRS::baro_data_message_t baro {179instance: 0,180pressure_pa: imu_data.pressure,181// setting temp to 25 effectively disables barometer temperature calibrations - these are already performed by MicroStrain182temperature: 25,183};184// *INDENT-ON*185AP::baro().handle_external(baro);186}187#endif188}189190void AP_ExternalAHRS_MicroStrain7::post_filter() const191{192{193WITH_SEMAPHORE(state.sem);194state.velocity = Vector3f{filter_data.ned_velocity_north, filter_data.ned_velocity_east, filter_data.ned_velocity_down};195state.have_velocity = true;196197// TODO the filter does not supply MSL altitude.198// The GNSS system has both MSL and WGS-84 ellipsoid height.199// Use GNSS 0 even though it may be bad.200state.location = Location{filter_data.lat, filter_data.lon, gnss_data[0].msl_altitude, Location::AltFrame::ABSOLUTE};201state.have_location = true;202203state.quat = filter_data.attitude_quat;204state.have_quaternion = true;205}206207for (int instance = 0; instance < NUM_GNSS_INSTANCES; instance++) {208// *INDENT-OFF*209AP_ExternalAHRS::gps_data_message_t gps {210gps_week: filter_data.week,211ms_tow: filter_data.tow_ms,212fix_type: AP_GPS_FixType(gnss_data[instance].fix_type),213satellites_in_view: gnss_data[instance].satellites,214215horizontal_pos_accuracy: gnss_data[instance].horizontal_position_accuracy,216vertical_pos_accuracy: gnss_data[instance].vertical_position_accuracy,217horizontal_vel_accuracy: gnss_data[instance].speed_accuracy,218219hdop: gnss_data[instance].hdop,220vdop: gnss_data[instance].vdop,221222longitude: gnss_data[instance].lon,223latitude: gnss_data[instance].lat,224msl_altitude: gnss_data[instance].msl_altitude,225226ned_vel_north: gnss_data[instance].ned_velocity_north,227ned_vel_east: gnss_data[instance].ned_velocity_east,228ned_vel_down: gnss_data[instance].ned_velocity_down,229};230// *INDENT-ON*231232if (gps.fix_type >= AP_GPS_FixType::FIX_3D && !state.have_origin) {233WITH_SEMAPHORE(state.sem);234state.origin = Location{int32_t(gnss_data[instance].lat),235int32_t(gnss_data[instance].lon),236int32_t(gnss_data[instance].msl_altitude),237Location::AltFrame::ABSOLUTE};238state.have_origin = true;239}240AP::gps().handle_external(gps, instance);241}242}243244int8_t AP_ExternalAHRS_MicroStrain7::get_port(void) const245{246if (!uart) {247return -1;248}249return port_num;250};251252// Get model/type name253const char* AP_ExternalAHRS_MicroStrain7::get_name() const254{255return "MicroStrain7";256}257258bool AP_ExternalAHRS_MicroStrain7::healthy(void) const259{260return times_healthy() && filter_healthy();261}262263bool AP_ExternalAHRS_MicroStrain7::initialised(void) const264{265const bool got_packets = last_imu_pkt != 0 && last_gps_pkt != 0 && last_filter_pkt != 0;266return got_packets;267}268269bool AP_ExternalAHRS_MicroStrain7::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const270{271if (!initialised()) {272hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "not initialised");273return false;274}275if (!times_healthy()) {276hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "data is stale");277return false;278}279if (!filter_healthy()) {280hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "filter is unhealthy");281return false;282}283if (!healthy()) {284hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "unhealthy");285return false;286}287static_assert(NUM_GNSS_INSTANCES == 2, "This check only works if there are two GPS types.");288if (gnss_data[0].fix_type < GPS_FIX_TYPE_3D_FIX && gnss_data[1].fix_type < GPS_FIX_TYPE_3D_FIX) {289hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "missing 3D GPS fix on either GPS");290return false;291}292293return true;294}295296void AP_ExternalAHRS_MicroStrain7::get_filter_status(nav_filter_status &status) const297{298memset(&status, 0, sizeof(status));299if (last_imu_pkt != 0 && last_gps_pkt != 0) {300status.flags.initalized = true;301}302if (healthy() && last_imu_pkt != 0) {303status.flags.attitude = true;304status.flags.vert_vel = true;305status.flags.vert_pos = true;306307const auto filter_state = static_cast<FilterState>(filter_status.state);308if (filter_state_healthy(filter_state)) {309status.flags.horiz_vel = true;310status.flags.horiz_pos_rel = true;311status.flags.horiz_pos_abs = true;312status.flags.pred_horiz_pos_rel = true;313status.flags.pred_horiz_pos_abs = true;314status.flags.using_gps = true;315}316}317}318319// get variances320bool AP_ExternalAHRS_MicroStrain7::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const321{322velVar = filter_data.ned_velocity_uncertainty.length() * vel_gate_scale;323posVar = filter_data.ned_position_uncertainty.xy().length() * pos_gate_scale;324hgtVar = filter_data.ned_position_uncertainty.z * hgt_gate_scale;325tasVar = 0;326return true;327}328329bool AP_ExternalAHRS_MicroStrain7::times_healthy() const330{331uint32_t now = AP_HAL::millis();332333// Expect the following rates:334// * Navigation Filter: 25Hz = 40mS335// * GPS: 2Hz = 500mS336// * IMU: 25Hz = 40mS337338// Allow for some slight variance of 10%339constexpr float RateFoS = 1.1;340341constexpr uint32_t expected_filter_time_delta_ms = 40;342constexpr uint32_t expected_gps_time_delta_ms = 500;343constexpr uint32_t expected_imu_time_delta_ms = 40;344345const bool times_healthy = (now - last_imu_pkt < expected_imu_time_delta_ms * RateFoS && \346now - last_gps_pkt < expected_gps_time_delta_ms * RateFoS && \347now - last_filter_pkt < expected_filter_time_delta_ms * RateFoS);348349return times_healthy;350}351352bool AP_ExternalAHRS_MicroStrain7::filter_healthy() const353{354const auto filter_state = static_cast<FilterState>(filter_status.state);355const bool filter_healthy = filter_state_healthy(filter_state);356return filter_healthy;357}358359bool AP_ExternalAHRS_MicroStrain7::filter_state_healthy(FilterState state)360{361switch (state) {362case FilterState::GQ7_FULL_NAV:363case FilterState::GQ7_AHRS:364return true;365default:366return false;367}368}369370#endif // AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED371372373