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.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 MIP parsing14*/1516#define ALLOW_DOUBLE_MATH_FUNCTIONS1718#include "AP_ExternalAHRS_config.h"1920#if AP_MICROSTRAIN_ENABLED2122#include "MicroStrain_common.h"23#include <AP_HAL/utility/sparse-endian.h>2425// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/sensor_data/sensor_data_links.htm26enum class INSPacketField {27ACCEL = 0x04,28GYRO = 0x05,29QUAT = 0x0A,30MAG = 0x06,31PRESSURE = 0x17,32};3334// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/gnss_recv_1/gnss_recv_1_links.htm35enum class GNSSPacketField {36LLH_POSITION = 0x03,37NED_VELOCITY = 0x05,38DOP_DATA = 0x07,39FIX_INFO = 0x0B,40// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/shared_data/data/mip_field_shared_gps_timestamp.htm41GPS_TIMESTAMP = 0xD3,42};4344// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/gnss_recv_1/data/mip_field_gnss_fix_info.htm45enum class GNSSFixType {46FIX_3D = 0x00,47FIX_2D = 0x01,48TIME_ONLY = 0x02,49NONE = 0x03,50INVALID = 0x04,51FIX_RTK_FLOAT = 0x05,52FIX_RTK_FIXED = 0x06,53};5455// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/filter_data/filter_data_links.htm56enum class FilterPacketField {57FILTER_STATUS = 0x10,58LLH_POSITION = 0x01,59NED_VELOCITY = 0x02,60// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/filter_data/data/mip_field_filter_attitude_quaternion.htm61ATTITUDE_QUAT = 0x03,62// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/0x82/data/0x08.htm63LLH_POSITION_UNCERTAINTY = 0x08,64// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/0x82/data/0x09.htm65NED_VELOCITY_UNCERTAINTY = 0x09,66// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/shared_data/data/mip_field_shared_gps_timestamp.htm67GPS_TIMESTAMP = 0xD3,68};6970bool AP_MicroStrain::handle_byte(const uint8_t b, DescriptorSet& descriptor)71{72switch (message_in.state) {73case ParseState::WaitingFor_SyncOne:74if (b == SYNC_ONE) {75message_in.packet.header[0] = b;76message_in.state = ParseState::WaitingFor_SyncTwo;77}78break;79case ParseState::WaitingFor_SyncTwo:80if (b == SYNC_TWO) {81message_in.packet.header[1] = b;82message_in.state = ParseState::WaitingFor_Descriptor;83} else {84message_in.state = ParseState::WaitingFor_SyncOne;85}86break;87case ParseState::WaitingFor_Descriptor:88message_in.packet.descriptor_set(b);89message_in.state = ParseState::WaitingFor_PayloadLength;90break;91case ParseState::WaitingFor_PayloadLength:92message_in.packet.payload_length(b);93message_in.state = ParseState::WaitingFor_Data;94message_in.index = 0;95break;96case ParseState::WaitingFor_Data:97message_in.packet.payload[message_in.index++] = b;98if (message_in.index >= message_in.packet.payload_length()) {99message_in.state = ParseState::WaitingFor_Checksum;100message_in.index = 0;101}102break;103case ParseState::WaitingFor_Checksum:104message_in.packet.checksum[message_in.index++] = b;105if (message_in.index >= 2) {106message_in.state = ParseState::WaitingFor_SyncOne;107message_in.index = 0;108109if (valid_packet(message_in.packet)) {110descriptor = handle_packet(message_in.packet);111return true;112}113}114break;115}116return false;117}118119bool AP_MicroStrain::valid_packet(const MicroStrain_Packet & packet)120{121uint8_t checksum_one = 0;122uint8_t checksum_two = 0;123124for (int i = 0; i < 4; i++) {125checksum_one += packet.header[i];126checksum_two += checksum_one;127}128129for (int i = 0; i < packet.payload_length(); i++) {130checksum_one += packet.payload[i];131checksum_two += checksum_one;132}133134return packet.checksum[0] == checksum_one && packet.checksum[1] == checksum_two;135}136137AP_MicroStrain::DescriptorSet AP_MicroStrain::handle_packet(const MicroStrain_Packet& packet)138{139const DescriptorSet descriptor = packet.descriptor_set();140switch (descriptor) {141case DescriptorSet::IMUData:142handle_imu(packet);143break;144case DescriptorSet::FilterData:145handle_filter(packet);146break;147case DescriptorSet::BaseCommand:148case DescriptorSet::DMCommand:149case DescriptorSet::SystemCommand:150break;151case DescriptorSet::GNSSData:152case DescriptorSet::GNSSRecv1:153case DescriptorSet::GNSSRecv2:154handle_gnss(packet);155break;156}157return descriptor;158}159160161void AP_MicroStrain::handle_imu(const MicroStrain_Packet& packet)162{163last_imu_pkt = AP_HAL::millis();164165// Iterate through fields of varying lengths in INS packet166for (uint8_t i = 0; i < packet.payload_length(); i += packet.payload[i]) {167switch ((INSPacketField) packet.payload[i+1]) {168// Scaled Ambient Pressure169case INSPacketField::PRESSURE: {170imu_data.pressure = be32tofloat_ptr(packet.payload, i+2) * 100; // Convert millibar to pascals171break;172}173// Scaled Magnetometer Vector174case INSPacketField::MAG: {175imu_data.mag = populate_vector3f(packet.payload, i+2) * 1000; // Convert gauss to milligauss176break;177}178// Scaled Accelerometer Vector179case INSPacketField::ACCEL: {180imu_data.accel = populate_vector3f(packet.payload, i+2) * GRAVITY_MSS; // Convert g's to m/s^2181break;182}183// Scaled Gyro Vector184case INSPacketField::GYRO: {185imu_data.gyro = populate_vector3f(packet.payload, i+2);186break;187}188// Quaternion189case INSPacketField::QUAT: {190imu_data.quat = populate_quaternion(packet.payload, i+2);191break;192}193}194}195}196197198void AP_MicroStrain::handle_gnss(const MicroStrain_Packet &packet)199{200last_gps_pkt = AP_HAL::millis();201uint8_t gnss_instance;202const DescriptorSet descriptor = DescriptorSet(packet.descriptor_set());203if (!get_gnss_instance(descriptor, gnss_instance)) {204return;205}206207// Iterate through fields of varying lengths in GNSS packet208for (uint8_t i = 0; i < packet.payload_length(); i += packet.payload[i]) {209switch ((GNSSPacketField) packet.payload[i+1]) {210case GNSSPacketField::GPS_TIMESTAMP: {211gnss_data[gnss_instance].tow_ms = double_to_uint32(be64todouble_ptr(packet.payload, i+2) * 1000); // Convert seconds to ms212gnss_data[gnss_instance].week = be16toh_ptr(&packet.payload[i+10]);213break;214}215case GNSSPacketField::FIX_INFO: {216switch ((GNSSFixType) packet.payload[i+2]) {217case (GNSSFixType::FIX_RTK_FLOAT): {218gnss_data[gnss_instance].fix_type = GPS_FIX_TYPE_RTK_FLOAT;219break;220}221case (GNSSFixType::FIX_RTK_FIXED): {222gnss_data[gnss_instance].fix_type = GPS_FIX_TYPE_RTK_FIXED;223break;224}225case (GNSSFixType::FIX_3D): {226gnss_data[gnss_instance].fix_type = GPS_FIX_TYPE_3D_FIX;227break;228}229case (GNSSFixType::FIX_2D): {230gnss_data[gnss_instance].fix_type = GPS_FIX_TYPE_2D_FIX;231break;232}233case (GNSSFixType::TIME_ONLY):234case (GNSSFixType::NONE): {235gnss_data[gnss_instance].fix_type = GPS_FIX_TYPE_NO_FIX;236break;237}238default:239case (GNSSFixType::INVALID): {240gnss_data[gnss_instance].fix_type = GPS_FIX_TYPE_NO_GPS;241break;242}243}244245gnss_data[gnss_instance].satellites = packet.payload[i+3];246break;247}248case GNSSPacketField::LLH_POSITION: {249gnss_data[gnss_instance].lat = be64todouble_ptr(packet.payload, i+2) * 1.0e7; // Decimal degrees to degrees250gnss_data[gnss_instance].lon = be64todouble_ptr(packet.payload, i+10) * 1.0e7;251gnss_data[gnss_instance].msl_altitude = be64todouble_ptr(packet.payload, i+26) * 1.0e2; // Meters to cm252gnss_data[gnss_instance].horizontal_position_accuracy = be32tofloat_ptr(packet.payload, i+34);253gnss_data[gnss_instance].vertical_position_accuracy = be32tofloat_ptr(packet.payload, i+38);254break;255}256case GNSSPacketField::DOP_DATA: {257gnss_data[gnss_instance].hdop = be32tofloat_ptr(packet.payload, i+10);258gnss_data[gnss_instance].vdop = be32tofloat_ptr(packet.payload, i+14);259break;260}261case GNSSPacketField::NED_VELOCITY: {262gnss_data[gnss_instance].ned_velocity_north = be32tofloat_ptr(packet.payload, i+2);263gnss_data[gnss_instance].ned_velocity_east = be32tofloat_ptr(packet.payload, i+6);264gnss_data[gnss_instance].ned_velocity_down = be32tofloat_ptr(packet.payload, i+10);265gnss_data[gnss_instance].speed_accuracy = be32tofloat_ptr(packet.payload, i+26);266break;267}268}269}270}271272void AP_MicroStrain::handle_filter(const MicroStrain_Packet &packet)273{274last_filter_pkt = AP_HAL::millis();275276// Iterate through fields of varying lengths in filter packet277for (uint8_t i = 0; i < packet.payload_length(); i += packet.payload[i]) {278switch ((FilterPacketField) packet.payload[i+1]) {279case FilterPacketField::GPS_TIMESTAMP: {280filter_data.tow_ms = be64todouble_ptr(packet.payload, i+2) * 1000; // Convert seconds to ms281filter_data.week = be16toh_ptr(&packet.payload[i+10]);282break;283}284case FilterPacketField::LLH_POSITION: {285filter_data.lat = be64todouble_ptr(packet.payload, i+2) * 1.0e7; // Decimal degrees to degrees286filter_data.lon = be64todouble_ptr(packet.payload, i+10) * 1.0e7;287filter_data.hae_altitude = be64todouble_ptr(packet.payload, i+26) * 1.0e2; // Meters to cm288break;289}290case FilterPacketField::NED_VELOCITY: {291filter_data.ned_velocity_north = be32tofloat_ptr(packet.payload, i+2);292filter_data.ned_velocity_east = be32tofloat_ptr(packet.payload, i+6);293filter_data.ned_velocity_down = be32tofloat_ptr(packet.payload, i+10);294break;295}296case FilterPacketField::ATTITUDE_QUAT: {297filter_data.attitude_quat = populate_quaternion(packet.payload, i+2);298filter_data.attitude_quat.normalize();299break;300}301case FilterPacketField::LLH_POSITION_UNCERTAINTY: {302const float north_pos_acc = be32tofloat_ptr(packet.payload, i+2);303const float east_pos_acc = be32tofloat_ptr(packet.payload, i+6);304const float down_pos_acc = be32tofloat_ptr(packet.payload, i+10);305filter_data.ned_position_uncertainty = Vector3f(306north_pos_acc,307east_pos_acc,308down_pos_acc309);310break;311}312case FilterPacketField::NED_VELOCITY_UNCERTAINTY: {313const float north_vel_uncertainty = be32tofloat_ptr(packet.payload, i+2);314const float east_vel_uncertainty = be32tofloat_ptr(packet.payload, i+6);315const float down_vel_uncertainty = be32tofloat_ptr(packet.payload, i+10);316filter_data.ned_velocity_uncertainty = Vector3f(317north_vel_uncertainty,318east_vel_uncertainty,319down_vel_uncertainty320);321break;322}323case FilterPacketField::FILTER_STATUS: {324filter_status.state = be16toh_ptr(&packet.payload[i+2]);325filter_status.mode = be16toh_ptr(&packet.payload[i+4]);326filter_status.flags = be16toh_ptr(&packet.payload[i+6]);327break;328}329}330}331}332333Vector3f AP_MicroStrain::populate_vector3f(const uint8_t *data, uint8_t offset)334{335return Vector3f {336be32tofloat_ptr(data, offset),337be32tofloat_ptr(data, offset+4),338be32tofloat_ptr(data, offset+8)339};340}341342Quaternion AP_MicroStrain::populate_quaternion(const uint8_t *data, uint8_t offset)343{344// https://github.com/clemense/quaternion-conventions345// AP follows W + Xi + Yj + Zk format.346// Microstrain follows the same347return Quaternion {348be32tofloat_ptr(data, offset),349be32tofloat_ptr(data, offset+4),350be32tofloat_ptr(data, offset+8),351be32tofloat_ptr(data, offset+12)352};353}354355bool AP_MicroStrain::get_gnss_instance(const DescriptorSet& descriptor, uint8_t& instance){356bool success = false;357358switch(descriptor) {359case DescriptorSet::GNSSData:360case DescriptorSet::GNSSRecv1:361instance = 0;362success = true;363break;364case DescriptorSet::GNSSRecv2:365instance = 1;366success = true;367break;368default:369break;370}371return success;372}373374375376#endif // AP_MICROSTRAIN_ENABLED377378