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/MicroStrain_common.h
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 MIP parsing14*/1516#pragma once1718#include "AP_ExternalAHRS_config.h"1920#if AP_MICROSTRAIN_ENABLED2122#include <AP_GPS/AP_GPS.h>23#include <AP_Math/vector3.h>24#include <AP_Math/quaternion.h>2526class AP_MicroStrain27{28public:293031protected:3233enum class ParseState {34WaitingFor_SyncOne,35WaitingFor_SyncTwo,36WaitingFor_Descriptor,37WaitingFor_PayloadLength,38WaitingFor_Data,39WaitingFor_Checksum40};4142struct {43Vector3f accel;44Vector3f gyro;45Vector3f mag;46Quaternion quat;47float pressure;48} imu_data;4950static constexpr uint8_t NUM_GNSS_INSTANCES = 2;5152struct {53uint16_t week;54uint32_t tow_ms;55GPS_FIX_TYPE fix_type;56uint8_t satellites;57float horizontal_position_accuracy;58float vertical_position_accuracy;59float hdop;60float vdop;61int32_t lon;62int32_t lat;63int32_t msl_altitude;64float ned_velocity_north;65float ned_velocity_east;66float ned_velocity_down;67float speed_accuracy;68} gnss_data[NUM_GNSS_INSTANCES];6970struct {71uint16_t state;72uint16_t mode;73uint16_t flags;74} filter_status;7576struct {77uint16_t week;78uint32_t tow_ms;79// 1-sigma position uncertainty in the NED local-level frame [meters].80Vector3f ned_position_uncertainty;81int32_t lon;82int32_t lat;83int32_t hae_altitude;84float ned_velocity_north;85float ned_velocity_east;86float ned_velocity_down;87// 1-sigma velocity uncertainties in the NED local-level frame.88Vector3f ned_velocity_uncertainty;89// 4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame.90// NED [Qw, Qx, Qy, Qz]91Quaternion attitude_quat;92} filter_data;9394enum class DescriptorSet {95BaseCommand = 0x01,96DMCommand = 0x0C,97SystemCommand = 0x7F,98IMUData = 0x80,99GNSSData = 0x81,100FilterData = 0x82,101GNSSRecv1 = 0x91,102GNSSRecv2 = 0x92103};104105const uint8_t SYNC_ONE = 0x75;106const uint8_t SYNC_TWO = 0x65;107108struct MicroStrain_Packet {109uint8_t header[4];110uint8_t payload[255];111uint8_t checksum[2];112113// Gets the payload length114uint8_t payload_length() const WARN_IF_UNUSED {115return header[3];116}117118// Sets the payload length119void payload_length(const uint8_t len) {120header[3] = len;121}122123// Gets the descriptor set124DescriptorSet descriptor_set() const WARN_IF_UNUSED {125return DescriptorSet(header[2]);126}127128// Sets the descriptor set (without validation)129void descriptor_set(const uint8_t descriptor_set) {130header[2] = descriptor_set;131}132};133134struct {135MicroStrain_Packet packet;136AP_MicroStrain::ParseState state;137uint8_t index;138} message_in;139140uint32_t last_imu_pkt;141uint32_t last_gps_pkt;142uint32_t last_filter_pkt;143144// Handle a single byte.145// If the byte matches a descriptor, it returns true and that type should be handled.146bool handle_byte(const uint8_t b, DescriptorSet& descriptor);147// Returns true if the fletcher checksum for the packet is valid, else false.148static bool valid_packet(const MicroStrain_Packet &packet);149// Calls the correct functions based on the packet descriptor of the packet150DescriptorSet handle_packet(const MicroStrain_Packet &packet);151// Collects data from an imu packet into `imu_data`152void handle_imu(const MicroStrain_Packet &packet);153// Collects data from a gnss packet into `gnss_data`154void handle_gnss(const MicroStrain_Packet &packet);155void handle_filter(const MicroStrain_Packet &packet);156static Vector3f populate_vector3f(const uint8_t* data, uint8_t offset);157static Quaternion populate_quaternion(const uint8_t* data, uint8_t offset);158// Depending on the descriptor, the data corresponds to a different GNSS instance.159static bool get_gnss_instance(const DescriptorSet& descriptor, uint8_t& instance);160};161162#endif // AP_MICROSTRAIN_ENABLED163164165