Path: blob/master/libraries/AP_ExternalAHRS/AP_ExternalAHRS_SBG.h
9767 views
/*1Copyright (C) 2025 Kraus Hamdani Aerospace Inc. All rights reserved.23This program is free software: you can redistribute it and/or modify4it under the terms of the GNU General Public License as published by5the Free Software Foundation, either version 3 of the License, or6(at your option) any later version.78This program is distributed in the hope that it will be useful,9but WITHOUT ANY WARRANTY; without even the implied warranty of10MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the11GNU General Public License for more details.1213You should have received a copy of the GNU General Public License14along with this program. If not, see <http://www.gnu.org/licenses/>.15*/16/*17support for serial connected SBG INS system18*/1920#pragma once2122#include "AP_ExternalAHRS_config.h"2324#if AP_EXTERNAL_AHRS_SBG_ENABLED2526#include "AP_ExternalAHRS_backend.h"27#include "AP_ExternalAHRS_SBG_structs.h"2829class AP_ExternalAHRS_SBG : public AP_ExternalAHRS_backend {3031public:32AP_ExternalAHRS_SBG(AP_ExternalAHRS *frontend, AP_ExternalAHRS::state_t &state);3334// get serial port number, -1 for not enabled35int8_t get_port(void) const override { return (uart == nullptr) ? -1 : port_num; }3637// accessors for AP_AHRS38bool healthy(void) const override { return last_received_ms > 0 && (AP_HAL::millis() - last_received_ms < 500); }39bool initialised(void) const override { return setup_complete; };40bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const override;4142void get_filter_status(nav_filter_status &status) const override;4344bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const override;4546// check for new data47void update() override { }4849// Get model/type name50const char* get_name() const override { return "SBG"; }5152protected:5354uint8_t num_gps_sensors(void) const override {55return 1;56}5758private:5960static constexpr uint8_t SBG_PACKET_SYNC1 = 0xFF;61static constexpr uint8_t SBG_PACKET_SYNC2 = 0x5A;62static constexpr uint8_t SBG_PACKET_ETX = 0x33;63static constexpr uint16_t SBG_PACKET_PAYLOAD_SIZE_MAX = 100; // real sbgCom limit is 4086 but the largest packet we parse is SbgEComLogEkfNav=72 bytes64static constexpr uint16_t SBG_PACKET_OVERHEAD = 9; // sync1, sync2, id, class, lenLSB, lenMSB, crcLSB, crcMSB, etx6566struct Cached {67struct {68AP_ExternalAHRS::gps_data_message_t gps_data;69AP_ExternalAHRS::mag_data_message_t mag_data;70AP_ExternalAHRS::baro_data_message_t baro_data;71AP_ExternalAHRS::ins_data_message_t ins_data;72AP_ExternalAHRS::airspeed_data_message_t airspeed_data;7374float baro_height;7576uint32_t gps_ms;77uint32_t mag_ms;78uint32_t baro_ms;79uint32_t ins_ms;80uint32_t airspeed_ms;81} sensors;8283struct {84SbgEComLogUtc utc;85SbgEComLogGnssVel gnssVel;86SbgEComLogGnssPos gnssPos;87SbgEComLogImuLegacy imuLegacy;88SbgEComLogImuFastLegacy imuFastLegacy;89SbgEComLogImuShort imuShort;90SbgEComLogEkfEuler ekfEuler;91SbgEComLogEkfQuat ekfQuat;92SbgEComLogEkfNav ekfNav; // biggest msg we care about, 72 bytes93SbgEComLogAirData airData;94SbgEComLogMag mag;95SbgEComDeviceInfo deviceInfo;96} sbg;97} cached;9899struct PACKED sbgMessage {100101uint8_t msgid = 0;102uint8_t msgclass = 0;103uint16_t len = 0;104uint8_t data[SBG_PACKET_PAYLOAD_SIZE_MAX];105106sbgMessage() {};107108sbgMessage(const uint8_t msgClass_, const uint8_t msgId_) {109msgid = msgId_;110msgclass = msgClass_;111};112113sbgMessage(const uint8_t msgClass_, const uint8_t msgId_, const uint8_t* payload, const uint16_t payload_len) {114msgid = msgId_;115msgclass = msgClass_;116117if (payload_len > 0 && payload_len <= sizeof(data)) {118memcpy(&data, payload, payload_len);119len = payload_len;120}121};122};123124enum class SBG_PACKET_PARSE_STATE : uint8_t {125SYNC1,126SYNC2,127MSG,128CLASS,129LEN1,130LEN2,131DATA,132CRC1,133CRC2,134ETX,135DROP_THIS_PACKET136};137138139struct SBG_PACKET_INBOUND_STATE {140SBG_PACKET_PARSE_STATE parser;141uint16_t data_count;142uint16_t crc;143sbgMessage msg;144uint16_t data_count_skip; // if we are parsing for a packet larger than we can accept, just stop parsing and wait for this many bytes to pass on by145} _inbound_state;146147void handle_msg(const sbgMessage &msg);148static bool parse_byte(const uint8_t data, sbgMessage &msg, SBG_PACKET_INBOUND_STATE &inbound_state);149void update_thread();150bool check_uart();151static uint16_t calcCRC(const void *pBuffer, uint16_t bufferSize);152static bool send_sbgMessage(AP_HAL::UARTDriver *_uart, const sbgMessage &msg);153static void safe_copy_msg_to_object(uint8_t* dest, const uint16_t dest_len, const uint8_t* src, const uint16_t src_len);154static uint16_t make_gps_week(const SbgEComLogUtc *utc_data);155156bool ekf_is_full_nav;157static bool SbgEkfStatus_is_fullNav(const uint32_t ekfStatus);158159static AP_GPS_FixType SbgGpsPosStatus_to_GpsFixType(const uint32_t gpsPosStatus);160161uint32_t send_MagData_ms;162uint32_t send_AirData_ms;163uint32_t send_mag_error_last_ms;164uint32_t send_air_error_last_ms;165static bool send_MagData(AP_HAL::UARTDriver *_uart);166static bool send_AirData(AP_HAL::UARTDriver *_uart);167168AP_HAL::UARTDriver *uart;169int8_t port_num;170uint32_t baudrate;171bool setup_complete;172uint32_t version_check_ms;173uint32_t last_received_ms;174};175176#endif // AP_EXTERNAL_AHRS_SBG_ENABLED177178179180