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_VectorNav.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#define ALLOW_DOUBLE_MATH_FUNCTIONS1920#include "AP_ExternalAHRS_config.h"2122#if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED2324#include "AP_ExternalAHRS_VectorNav.h"25#include <AP_Math/AP_Math.h>26#include <AP_Math/crc.h>27#include <AP_Baro/AP_Baro.h>28#include <AP_Compass/AP_Compass.h>29#include <AP_GPS/AP_GPS.h>30#include <AP_InertialSensor/AP_InertialSensor.h>31#include <GCS_MAVLink/GCS.h>32#include <AP_Logger/AP_Logger.h>33#include <AP_SerialManager/AP_SerialManager.h>34#include <AP_Common/NMEA.h>35#include <stdio.h>36#include <AP_BoardConfig/AP_BoardConfig.h>3738extern const AP_HAL::HAL &hal;394041/*42TYPE::VN_AHRS configures 2 packets: high-rate IMU and mid-rate EKF43Header for IMU packet44$VNWRG,75,3,16,01,0721*D41545Common group (Group 1)46TimeStartup47AngularRate48Accel49Imu50MagPres51Header for EKF packet52$VNWRG,76,3,16,11,0001,0106*B36B53Common group (Group 1)54TimeStartup55Attitude group (Group 4)56Ypr57Quaternion58YprU59*/6061struct PACKED VN_IMU_packet {62static constexpr uint8_t header[]{0x01, 0x21, 0x07};63uint64_t timeStartup;64float gyro[3];65float accel[3];66float uncompAccel[3];67float uncompAngRate[3];68float mag[3];69float temp;70float pressure;71};72constexpr uint8_t VN_IMU_packet::header[];73constexpr uint8_t VN_IMU_LENGTH = sizeof(VN_IMU_packet) + sizeof(VN_IMU_packet::header) + 1 + 2; // Includes sync byte and CRC7475struct PACKED VN_AHRS_ekf_packet {76static constexpr uint8_t header[]{0x11, 0x01, 0x00, 0x06, 0x01};77uint64_t timeStartup;78float ypr[3];79float quaternion[4];80float yprU[3];81};82constexpr uint8_t VN_AHRS_ekf_packet::header[];83constexpr uint8_t VN_AHRS_EKF_LENGTH = sizeof(VN_AHRS_ekf_packet) + sizeof(VN_AHRS_ekf_packet::header) + 1 + 2; // Includes sync byte and CRC8485/*86TYPE::VN_INS configures 3 packets: high-rate IMU, mid-rate EKF, and 5Hz GNSS87Header for IMU packet88$VNWRG,75,3,16,01,0721*D41589Common group (Group 1)90TimeStartup91AngularRate92Accel93Imu94MagPres95Header for EKF packet96$VNWRG,76,3,16,31,0001,0106,0613*097A97Common group (Group 1)98TimeStartup99Attitude group (Group 4)100Ypr101Quaternion102YprU103Ins group (Group 5)104InsStatus105PosLla106VelNed107PosU108VelU109Header for GNSS packet110$VNWRG,77,1,160,49,0003,26B8,0018*4FD9111Common group (Group 1)112TimeStartup113TimeGps114Gnss1 group (Group 3)115NumSats116GnssFix117GnssPosLla118GnssVelNed119PosU1120VelU1121GnssDop122Gnss2 group (Group 6)123NumSats124GnssFix125*/126127union Ins_Status {128uint16_t _value;129struct {130uint16_t mode : 2;131uint16_t gnssFix : 1;132uint16_t resv1 : 2;133uint16_t imuErr : 1;134uint16_t magPresErr : 1;135uint16_t gnssErr : 1;136uint16_t resv2 : 1;137uint16_t gnssHeadingIns : 2;138};139};140141struct PACKED VN_INS_ekf_packet {142static constexpr uint8_t header[]{0x31, 0x01, 0x00, 0x06, 0x01, 0x13, 0x06};143uint64_t timeStartup;144float ypr[3];145float quaternion[4];146float yprU[3];147uint16_t insStatus;148double posLla[3];149float velNed[3];150float posU;151float velU;152};153constexpr uint8_t VN_INS_ekf_packet::header[];154constexpr uint8_t VN_INS_EKF_LENGTH = sizeof(VN_INS_ekf_packet) + sizeof(VN_INS_ekf_packet::header) + 1 + 2; // Includes sync byte and CRC155156struct PACKED VN_INS_gnss_packet {157static constexpr uint8_t header[]{0x49, 0x03, 0x00, 0xB8, 0x26, 0x18, 0x00};158uint64_t timeStartup;159uint64_t timeGps;160uint8_t numSats1;161uint8_t fix1;162double posLla1[3];163float velNed1[3];164float posU1[3];165float velU1;166float dop1[7];167uint8_t numSats2;168uint8_t fix2;169};170constexpr uint8_t VN_INS_gnss_packet::header[];171constexpr uint8_t VN_INS_GNSS_LENGTH = sizeof(VN_INS_gnss_packet) + sizeof(VN_INS_gnss_packet::header) + 1 + 2; // Includes sync byte and CRC172173// constructor174AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend,175AP_ExternalAHRS::state_t &_state) :176AP_ExternalAHRS_backend(_frontend, _state)177{178auto &sm = AP::serialmanager();179uart = sm.find_serial(AP_SerialManager::SerialProtocol_AHRS, 0);180if (!uart) {181GCS_SEND_TEXT(MAV_SEVERITY_INFO, "VectorNav ExternalAHRS no UART");182return;183}184baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0);185port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0);186187bufsize = MAX(MAX(MAX(VN_IMU_LENGTH, VN_INS_EKF_LENGTH), VN_INS_GNSS_LENGTH), VN_AHRS_EKF_LENGTH);188189pktbuf = NEW_NOTHROW uint8_t[bufsize];190latest_ins_ekf_packet = NEW_NOTHROW VN_INS_ekf_packet;191latest_ins_gnss_packet = NEW_NOTHROW VN_INS_gnss_packet;192193if (!pktbuf || !latest_ins_ekf_packet) {194AP_BoardConfig::allocation_error("VectorNav ExternalAHRS");195}196197if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_VectorNav::update_thread, void), "AHRS", 2048, AP_HAL::Scheduler::PRIORITY_SPI, 0)) {198AP_HAL::panic("VectorNav Failed to start ExternalAHRS update thread");199}200GCS_SEND_TEXT(MAV_SEVERITY_INFO, "VectorNav ExternalAHRS initialised");201}202203/*204check the UART for more data205returns true if the function should be called again straight away206*/207#define SYNC_BYTE 0xFA208bool AP_ExternalAHRS_VectorNav::check_uart()209{210if (!setup_complete) {211return false;212}213WITH_SEMAPHORE(state.sem);214// ensure we own the uart215uart->begin(0);216uint32_t n = uart->available();217if (n == 0) {218return false;219}220if (pktoffset < bufsize) {221ssize_t nread = uart->read(&pktbuf[pktoffset], MIN(n, unsigned(bufsize-pktoffset)));222if (nread <= 0) {223return false;224}225pktoffset += nread;226}227228bool match_header1 = false;229bool match_header2 = false;230bool match_header3 = false;231bool match_header4 = false;232233if (pktbuf[0] != SYNC_BYTE) {234goto reset;235}236237238match_header1 = (0 == memcmp(&pktbuf[1], VN_IMU_packet::header, MIN(sizeof(VN_IMU_packet::header), unsigned(pktoffset - 1))));239if (type == TYPE::VN_AHRS) {240match_header2 = (0 == memcmp(&pktbuf[1], VN_AHRS_ekf_packet::header, MIN(sizeof(VN_AHRS_ekf_packet::header), unsigned(pktoffset - 1))));241} else {242match_header3 = (0 == memcmp(&pktbuf[1], VN_INS_ekf_packet::header, MIN(sizeof(VN_INS_ekf_packet::header), unsigned(pktoffset - 1))));243match_header4 = (0 == memcmp(&pktbuf[1], VN_INS_gnss_packet::header, MIN(sizeof(VN_INS_gnss_packet::header), unsigned(pktoffset - 1))));244}245if (!match_header1 && !match_header2 && !match_header3 && !match_header4) {246goto reset;247}248249if (match_header1 && pktoffset >= VN_IMU_LENGTH) {250uint16_t crc = crc16_ccitt(&pktbuf[1], VN_IMU_LENGTH - 1, 0);251if (crc == 0) {252process_imu_packet(&pktbuf[sizeof(VN_IMU_packet::header) + 1]);253memmove(&pktbuf[0], &pktbuf[VN_IMU_LENGTH], pktoffset - VN_IMU_LENGTH);254pktoffset -= VN_IMU_LENGTH;255} else {256goto reset;257}258} else if (match_header2 && pktoffset >= VN_AHRS_EKF_LENGTH) {259uint16_t crc = crc16_ccitt(&pktbuf[1], VN_AHRS_EKF_LENGTH - 1, 0);260if (crc == 0) {261process_ahrs_ekf_packet(&pktbuf[sizeof(VN_AHRS_ekf_packet::header) + 1]);262memmove(&pktbuf[0], &pktbuf[VN_AHRS_EKF_LENGTH], pktoffset - VN_AHRS_EKF_LENGTH);263pktoffset -= VN_AHRS_EKF_LENGTH;264} else {265goto reset;266}267} else if (match_header3 && pktoffset >= VN_INS_EKF_LENGTH) {268uint16_t crc = crc16_ccitt(&pktbuf[1], VN_INS_EKF_LENGTH - 1, 0);269if (crc == 0) {270process_ins_ekf_packet(&pktbuf[sizeof(VN_INS_ekf_packet::header) + 1]);271memmove(&pktbuf[0], &pktbuf[VN_INS_EKF_LENGTH], pktoffset - VN_INS_EKF_LENGTH);272pktoffset -= VN_INS_EKF_LENGTH;273} else {274goto reset;275}276} else if (match_header4 && pktoffset >= VN_INS_GNSS_LENGTH) {277uint16_t crc = crc16_ccitt(&pktbuf[1], VN_INS_GNSS_LENGTH - 1, 0);278if (crc == 0) {279process_ins_gnss_packet(&pktbuf[sizeof(VN_INS_gnss_packet::header) + 1]);280memmove(&pktbuf[0], &pktbuf[VN_INS_GNSS_LENGTH], pktoffset - VN_INS_GNSS_LENGTH);281pktoffset -= VN_INS_GNSS_LENGTH;282} else {283goto reset;284}285}286return true;287288reset:289uint8_t *p = (uint8_t *)memchr(&pktbuf[1], SYNC_BYTE, pktoffset-1);290if (p) {291uint8_t newlen = pktoffset - (p - pktbuf);292memmove(&pktbuf[0], p, newlen);293pktoffset = newlen;294} else {295pktoffset = 0;296}297return true;298}299300// Send command and wait for response301// Only run from thread! This blocks and retries until a non-error response is received302#define READ_REQUEST_RETRY_MS 500303void AP_ExternalAHRS_VectorNav::run_command(const char * fmt, ...)304{305va_list ap;306307va_start(ap, fmt);308hal.util->vsnprintf(message_to_send, sizeof(message_to_send), fmt, ap);309va_end(ap);310311uint32_t request_sent = 0;312while (true) {313hal.scheduler->delay(1);314315const uint32_t now = AP_HAL::millis();316if (now - request_sent > READ_REQUEST_RETRY_MS) {317nmea_printf(uart, "$%s", message_to_send);318request_sent = now;319}320321int16_t nbytes = uart->available();322while (nbytes-- > 0) {323char c = uart->read();324if (decode(c)) {325if (nmea.error_response && nmea.sentence_done) {326// Received a valid VNERR. Try to resend after the timeout length327break;328}329return;330}331}332}333}334335// add a single character to the buffer and attempt to decode336// returns true if a complete sentence was successfully decoded337bool AP_ExternalAHRS_VectorNav::decode(char c)338{339switch (c) {340case ',':341// end of a term, add to checksum342nmea.checksum ^= c;343FALLTHROUGH;344case '\r':345case '\n':346case '*':347{348if (nmea.sentence_done) {349return false;350}351if (nmea.term_is_checksum) {352nmea.sentence_done = true;353uint8_t checksum = 16 * char_to_hex(nmea.term[0]) + char_to_hex(nmea.term[1]);354return ((checksum == nmea.checksum) && nmea.sentence_valid);355}356357// null terminate and decode latest term358nmea.term[nmea.term_offset] = 0;359if (nmea.sentence_valid) {360nmea.sentence_valid = decode_latest_term();361}362363// move onto next term364nmea.term_number++;365nmea.term_offset = 0;366nmea.term_is_checksum = (c == '*');367return false;368}369370case '$': // sentence begin371nmea.sentence_valid = true;372nmea.term_number = 0;373nmea.term_offset = 0;374nmea.checksum = 0;375nmea.term_is_checksum = false;376nmea.sentence_done = false;377nmea.error_response = false;378return false;379}380381// ordinary characters are added to term382if (nmea.term_offset < sizeof(nmea.term) - 1) {383nmea.term[nmea.term_offset++] = c;384}385if (!nmea.term_is_checksum) {386nmea.checksum ^= c;387}388389return false;390}391392// decode the most recently consumed term393// returns true if new term is valid394bool AP_ExternalAHRS_VectorNav::decode_latest_term()395{396// Check the first two terms (In most cases header + reg number) that they match the sent397// message. If not, the response is invalid.398switch (nmea.term_number) {399case 0:400if (strncmp(nmea.term, "VNERR", nmea.term_offset) == 0) {401nmea.error_response = true; // Message will be printed on next term402} else if (strncmp(nmea.term, message_to_send, nmea.term_offset) != 0) {403return false;404}405return true;406case 1:407if (nmea.error_response) {408GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "VectorNav received VNERR code: %s", nmea.term);409} else if (strlen(message_to_send) > 6 &&410strncmp(nmea.term, &message_to_send[6], nmea.term_offset) != 0) { // Start after "VNXXX,"411return false;412}413return true;414case 2:415if (strncmp(nmea.term, "VN-", 3) == 0) {416// This term is the model number417strncpy(model_name, nmea.term, sizeof(model_name));418}419return true;420default:421return true;422}423}424425void AP_ExternalAHRS_VectorNav::initialize() {426// Open port in the thread427uart->begin(baudrate, 1024, 512);428429// Pause asynchronous communications to simplify packet finding430run_command("VNASY,0");431432// Stop ASCII async outputs for both UARTs. If only active UART is disabled, we get a baudrate433// overflow on the other UART when configuring binary outputs (reg 75 and 76) to both UARTs434run_command("VNWRG,06,0,1");435run_command("VNWRG,06,0,2");436437// Read Model Number Register, ID 1438run_command("VNRRG,01");439440// Setup for messages respective model types (on both UARTs)441if (strncmp(model_name, "VN-1", 4) == 0) {442// VN-1X0443type = TYPE::VN_AHRS;444445// These assumes unit is still configured at its default rate of 800hz446run_command("VNWRG,75,3,%u,01,0721", unsigned(800 / get_rate()));447run_command("VNWRG,76,3,16,11,0001,0106");448} else {449// Default to setup for sensors other than VN-100 or VN-110450// This assumes unit is still configured at its default IMU rate of 400hz for VN-300, 800hz for others451uint16_t imu_rate = 800; // Default for everything but VN-300452if (strncmp(model_name, "VN-300", 6) == 0) {453imu_rate = 400;454}455if (strncmp(model_name, "VN-3", 4) == 0) {456has_dual_gnss = true;457}458run_command("VNWRG,75,3,%u,01,0721", unsigned(imu_rate / get_rate()));459run_command("VNWRG,76,3,%u,31,0001,0106,0613", unsigned(imu_rate / 50));460run_command("VNWRG,77,3,%u,49,0003,26B8,0018", unsigned(imu_rate / 5));461}462463// Resume asynchronous communications464run_command("VNASY,1");465setup_complete = true;466}467468void AP_ExternalAHRS_VectorNav::update_thread() {469initialize();470while (true) {471if (!check_uart()) {472hal.scheduler->delay(1);473}474}475}476477const char* AP_ExternalAHRS_VectorNav::get_name() const478{479if (setup_complete) {480return model_name;481}482return nullptr;483}484485// Input data struct for EAHA logging message, used by both AHRS mode and INS mode486struct AP_ExternalAHRS_VectorNav::VNAT {487uint64_t timeUs;488float quat[4];489float ypr[3];490float yprU[3];491};492493494void AP_ExternalAHRS_VectorNav::write_vnat(const VNAT& data_to_log) const {495496#if HAL_LOGGING_ENABLED497// @LoggerMessage: VNAT498// @Description: VectorNav Attitude data499// @Field: TimeUS: Time since system startup500// @Field: Q1: Attitude quaternion 1501// @Field: Q2: Attitude quaternion 2502// @Field: Q3: Attitude quaternion 3503// @Field: Q4: Attitude quaternion 4504// @Field: Yaw: Yaw505// @Field: Pitch: Pitch506// @Field: Roll: Roll507// @Field: YU: Yaw unceratainty508// @Field: PU: Pitch uncertainty509// @Field: RU: Roll uncertainty510511AP::logger().WriteStreaming("VNAT", "TimeUS,Q1,Q2,Q3,Q4,Yaw,Pitch,Roll,YU,PU,RU",512"s----dddddd", "F0000000000",513"Qffffffffff",514data_to_log.timeUs,515data_to_log.quat[0], data_to_log.quat[1], data_to_log.quat[2], data_to_log.quat[3],516data_to_log.ypr[0], data_to_log.ypr[1], data_to_log.ypr[2],517data_to_log.yprU[0], data_to_log.yprU[1], data_to_log.yprU[2]);518#endif519}520521522523// process INS mode INS packet524void AP_ExternalAHRS_VectorNav::process_imu_packet(const uint8_t *b)525{526const struct VN_IMU_packet &pkt = *(struct VN_IMU_packet *)b;527528last_pkt1_ms = AP_HAL::millis();529530const bool use_uncomp = option_is_set(AP_ExternalAHRS::OPTIONS::VN_UNCOMP_IMU);531532{533WITH_SEMAPHORE(state.sem);534if (use_uncomp) {535state.accel = Vector3f{pkt.uncompAccel[0], pkt.uncompAccel[1], pkt.uncompAccel[2]};536state.gyro = Vector3f{pkt.uncompAngRate[0], pkt.uncompAngRate[1], pkt.uncompAngRate[2]};537} else {538state.accel = Vector3f{pkt.accel[0], pkt.accel[1], pkt.accel[2]};539state.gyro = Vector3f{pkt.gyro[0], pkt.gyro[1], pkt.gyro[2]};540}541}542543#if AP_BARO_EXTERNALAHRS_ENABLED544{545AP_ExternalAHRS::baro_data_message_t baro;546baro.instance = 0;547baro.pressure_pa = pkt.pressure * 1e3;548baro.temperature = pkt.temp;549550AP::baro().handle_external(baro);551}552#endif553554#if AP_COMPASS_EXTERNALAHRS_ENABLED555{556AP_ExternalAHRS::mag_data_message_t mag;557mag.field = Vector3f{pkt.mag[0], pkt.mag[1], pkt.mag[2]};558mag.field *= 1000; // to mGauss559560AP::compass().handle_external(mag);561}562#endif563564{565AP_ExternalAHRS::ins_data_message_t ins;566567ins.accel = state.accel;568ins.gyro = state.gyro;569ins.temperature = pkt.temp;570571AP::ins().handle_external(ins);572}573574#if HAL_LOGGING_ENABLED575// @LoggerMessage: VNIM576// @Description: VectorNav IMU data577// @Field: TimeUS: Time since system startup578// @Field: Temp: Temprature579// @Field: Pres: Pressure580// @Field: MX: Magnetic feild X-axis581// @Field: MY: Magnetic feild Y-axis582// @Field: MZ: Magnetic feild Z-axis583// @Field: AX: Acceleration X-axis584// @Field: AY: Acceleration Y-axis585// @Field: AZ: Acceleration Z-axis586// @Field: GX: Rotation rate X-axis587// @Field: GY: Rotation rate Y-axis588// @Field: GZ: Rotation rate Z-axis589590AP::logger().WriteStreaming("VNIM", "TimeUS,Temp,Pres,MX,MY,MZ,AX,AY,AZ,GX,GY,GZ",591"sdPGGGoooEEE", "F00000000000",592"Qfffffffffff",593AP_HAL::micros64(),594pkt.temp, pkt.pressure*1e3,595pkt.mag[0], pkt.mag[1], pkt.mag[2],596state.accel[0], state.accel[1], state.accel[2],597state.gyro[0], state.gyro[1], state.gyro[2],598state.quat[0], state.quat[1], state.quat[2], state.quat[3]);599#endif // HAL_LOGGING_ENABLED600}601602// process AHRS mode AHRS packet603void AP_ExternalAHRS_VectorNav::process_ahrs_ekf_packet(const uint8_t *b) {604const struct VN_AHRS_ekf_packet &pkt = *(struct VN_AHRS_ekf_packet *)b;605606last_pkt2_ms = AP_HAL::millis();607608state.quat = Quaternion{pkt.quaternion[3], pkt.quaternion[0], pkt.quaternion[1], pkt.quaternion[2]};609state.have_quaternion = true;610611#if HAL_LOGGING_ENABLED612VNAT data_to_log;613data_to_log.timeUs = AP_HAL::micros64();614memcpy(data_to_log.quat, pkt.quaternion, sizeof(pkt.quaternion));615memcpy(data_to_log.ypr, pkt.ypr, sizeof(pkt.ypr));616memcpy(data_to_log.yprU, pkt.yprU, sizeof(pkt.yprU));617618write_vnat(data_to_log);619#endif // HAL_LOGGING_ENABLED620}621622// process INS mode EKF packet623void AP_ExternalAHRS_VectorNav::process_ins_ekf_packet(const uint8_t *b) {624const struct VN_INS_ekf_packet &pkt = *(struct VN_INS_ekf_packet *)b;625626last_pkt2_ms = AP_HAL::millis();627*latest_ins_ekf_packet = pkt;628629state.quat = Quaternion{pkt.quaternion[3], pkt.quaternion[0], pkt.quaternion[1], pkt.quaternion[2]};630state.have_quaternion = true;631632state.velocity = Vector3f{pkt.velNed[0], pkt.velNed[1], pkt.velNed[2]};633state.have_velocity = true;634635state.location = Location{int32_t(pkt.posLla[0] * 1.0e7), int32_t(pkt.posLla[1] * 1.0e7), int32_t(pkt.posLla[2] * 1.0e2), Location::AltFrame::ABSOLUTE};636state.last_location_update_us = AP_HAL::micros();637state.have_location = true;638639#if HAL_LOGGING_ENABLED640VNAT data_to_log;641auto now = AP_HAL::micros64();642data_to_log.timeUs = now;643memcpy(data_to_log.quat, pkt.quaternion, sizeof(pkt.quaternion));644memcpy(data_to_log.ypr, pkt.ypr, sizeof(pkt.ypr));645memcpy(data_to_log.yprU, pkt.yprU, sizeof(pkt.yprU));646write_vnat(data_to_log);647648// @LoggerMessage: VNKF649// @Description: VectorNav INS Kalman Filter data650// @Field: TimeUS: Time since system startup651// @Field: InsStatus: VectorNav INS health status652// @Field: Lat: Latitude653// @Field: Lon: Longitude654// @Field: Alt: Altitude655// @Field: VelN: Velocity Northing656// @Field: VelE: Velocity Easting657// @Field: VelD: Velocity Downing658// @Field: PosU: Filter estimated position uncertainty659// @Field: VelU: Filter estimated Velocity uncertainty660661AP::logger().WriteStreaming("VNKF", "TimeUS,InsStatus,Lat,Lon,Alt,VelN,VelE,VelD,PosU,VelU",662"s-ddmnnndn", "F000000000",663"QHdddfffff",664now,665pkt.insStatus,666pkt.posLla[0], pkt.posLla[1], pkt.posLla[2],667pkt.velNed[0], pkt.velNed[1], pkt.velNed[2],668pkt.posU, pkt.velU);669#endif // HAL_LOGGING_ENABLED670671}672673// process INS mode GNSS packet674void AP_ExternalAHRS_VectorNav::process_ins_gnss_packet(const uint8_t *b) {675const struct VN_INS_gnss_packet &pkt = *(struct VN_INS_gnss_packet *)b;676AP_ExternalAHRS::gps_data_message_t gps;677678679last_pkt3_ms = AP_HAL::millis();680*latest_ins_gnss_packet = pkt;681682// get ToW in milliseconds683gps.gps_week = pkt.timeGps / (AP_MSEC_PER_WEEK * 1000000ULL);684gps.ms_tow = (pkt.timeGps / 1000000ULL) % (60 * 60 * 24 * 7 * 1000ULL);685gps.fix_type = AP_GPS_FixType(pkt.fix1);686gps.satellites_in_view = pkt.numSats1;687688gps.horizontal_pos_accuracy = pkt.posU1[0];689gps.vertical_pos_accuracy = pkt.posU1[2];690gps.horizontal_vel_accuracy = pkt.velU1;691692gps.hdop = pkt.dop1[4];693gps.vdop = pkt.dop1[3];694695gps.latitude = pkt.posLla1[0] * 1.0e7;696gps.longitude = pkt.posLla1[1] * 1.0e7;697gps.msl_altitude = pkt.posLla1[2] * 1.0e2;698699gps.ned_vel_north = pkt.velNed1[0];700gps.ned_vel_east = pkt.velNed1[1];701gps.ned_vel_down = pkt.velNed1[2];702703if (!state.have_origin && gps.fix_type >= AP_GPS_FixType::FIX_3D) {704WITH_SEMAPHORE(state.sem);705state.origin = Location{int32_t(pkt.posLla1[0] * 1.0e7), int32_t(pkt.posLla1[1] * 1.0e7),706int32_t(pkt.posLla1[2] * 1.0e2), Location::AltFrame::ABSOLUTE};707state.have_origin = true;708}709uint8_t instance;710if (AP::gps().get_first_external_instance(instance)) {711AP::gps().handle_external(gps, instance);712}713}714715// get serial port number for the uart716int8_t AP_ExternalAHRS_VectorNav::get_port(void) const717{718if (!uart) {719return -1;720}721return port_num;722};723724// accessors for AP_AHRS725bool AP_ExternalAHRS_VectorNav::healthy(void) const726{727const uint32_t now = AP_HAL::millis();728return (now - last_pkt1_ms < 40) && (now - last_pkt2_ms < 500) && (type == TYPE::VN_AHRS ? true: now - last_pkt3_ms < 1000);729}730731bool AP_ExternalAHRS_VectorNav::initialised(void) const732{733if (!setup_complete) {734return false;735}736return last_pkt1_ms != UINT32_MAX && last_pkt2_ms != UINT32_MAX && (type == TYPE::VN_AHRS ? true : last_pkt3_ms != UINT32_MAX);737}738739bool AP_ExternalAHRS_VectorNav::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const740{741if (!setup_complete) {742hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav setup failed");743return false;744}745if (!healthy()) {746hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav unhealthy");747return false;748}749if (type == TYPE::VN_INS) {750if (latest_ins_gnss_packet->fix1 < 3) {751hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav no GPS1 lock");752return false;753}754if (has_dual_gnss && (latest_ins_gnss_packet->fix2 < 3)) {755hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav no GPS2 lock");756return false;757}758}759return true;760}761762/*763get filter status. We don't know the meaning of the status bits yet,764so assume all OK if we have GPS lock765*/766void AP_ExternalAHRS_VectorNav::get_filter_status(nav_filter_status &status) const767{768memset(&status, 0, sizeof(status));769status.flags.initalized = initialised();770if (healthy()) {771if (type == TYPE::VN_AHRS) {772status.flags.attitude = true;773} else {774status.flags.attitude = true;775if (latest_ins_ekf_packet) {776status.flags.vert_vel = true;777status.flags.vert_pos = true;778779status.flags.horiz_vel = true;780status.flags.horiz_pos_rel = true;781status.flags.horiz_pos_abs = true;782status.flags.pred_horiz_pos_rel = true;783status.flags.pred_horiz_pos_abs = true;784status.flags.using_gps = true;785}786}787}788}789790// get variances791bool AP_ExternalAHRS_VectorNav::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const792{793const struct VN_INS_ekf_packet &pkt = *(struct VN_INS_ekf_packet *)latest_ins_ekf_packet;794velVar = pkt.velU * vel_gate_scale;795posVar = pkt.posU * pos_gate_scale;796hgtVar = pkt.posU * hgt_gate_scale;797tasVar = 0;798return true;799}800801#endif // AP_EXTERNAL_AHRS_VECTORNAV_ENABLED802803804