Path: blob/master/libraries/AP_ExternalAHRS/MicroStrain_common.cpp
9447 views
/*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 AP_MATH_ALLOW_DOUBLE_FUNCTIONS 11718#include "AP_ExternalAHRS_config.h"19#include <AP_GPS/AP_GPS.h>2021#if AP_MICROSTRAIN_ENABLED2223#include "MicroStrain_common.h"24#include <AP_HAL/utility/sparse-endian.h>2526// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/sensor_data/sensor_data_links.htm27enum class INSPacketField {28ACCEL = 0x04,29GYRO = 0x05,30QUAT = 0x0A,31MAG = 0x06,32PRESSURE = 0x17,33};3435// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/gnss_recv_1/gnss_recv_1_links.htm36enum class GNSSPacketField {37LLH_POSITION = 0x03,38NED_VELOCITY = 0x05,39DOP_DATA = 0x07,40FIX_INFO = 0x0B,41// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/shared_data/data/mip_field_shared_gps_timestamp.htm42GPS_TIMESTAMP = 0xD3,43};4445// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/gnss_recv_1/data/mip_field_gnss_fix_info.htm46enum class GNSSFixType {47FIX_3D = 0x00,48FIX_2D = 0x01,49TIME_ONLY = 0x02,50NONE = 0x03,51INVALID = 0x04,52FIX_RTK_FLOAT = 0x05,53FIX_RTK_FIXED = 0x06,54};5556// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/filter_data/filter_data_links.htm57enum class FilterPacketField {58FILTER_STATUS = 0x10,59LLH_POSITION = 0x01,60NED_VELOCITY = 0x02,61// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/filter_data/data/mip_field_filter_attitude_quaternion.htm62ATTITUDE_QUAT = 0x03,63// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/0x82/data/0x08.htm64LLH_POSITION_UNCERTAINTY = 0x08,65// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/0x82/data/0x09.htm66NED_VELOCITY_UNCERTAINTY = 0x09,67// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/shared_data/data/mip_field_shared_gps_timestamp.htm68GPS_TIMESTAMP = 0xD3,69};7071bool AP_MicroStrain::handle_byte(const uint8_t b, DescriptorSet& descriptor)72{73switch (message_in.state) {74case ParseState::WaitingFor_SyncOne:75if (b == SYNC_ONE) {76message_in.packet.header[0] = b;77message_in.state = ParseState::WaitingFor_SyncTwo;78}79break;80case ParseState::WaitingFor_SyncTwo:81if (b == SYNC_TWO) {82message_in.packet.header[1] = b;83message_in.state = ParseState::WaitingFor_Descriptor;84} else {85message_in.state = ParseState::WaitingFor_SyncOne;86}87break;88case ParseState::WaitingFor_Descriptor:89message_in.packet.descriptor_set(b);90message_in.state = ParseState::WaitingFor_PayloadLength;91break;92case ParseState::WaitingFor_PayloadLength:93message_in.packet.payload_length(b);94message_in.state = ParseState::WaitingFor_Data;95message_in.index = 0;96break;97case ParseState::WaitingFor_Data:98message_in.packet.payload[message_in.index++] = b;99if (message_in.index >= message_in.packet.payload_length()) {100message_in.state = ParseState::WaitingFor_Checksum;101message_in.index = 0;102}103break;104case ParseState::WaitingFor_Checksum:105message_in.packet.checksum[message_in.index++] = b;106if (message_in.index >= 2) {107message_in.state = ParseState::WaitingFor_SyncOne;108message_in.index = 0;109110if (valid_packet(message_in.packet)) {111descriptor = handle_packet(message_in.packet);112return true;113}114}115break;116}117return false;118}119120bool AP_MicroStrain::valid_packet(const MicroStrain_Packet & packet)121{122uint8_t checksum_one = 0;123uint8_t checksum_two = 0;124125for (int i = 0; i < 4; i++) {126checksum_one += packet.header[i];127checksum_two += checksum_one;128}129130for (int i = 0; i < packet.payload_length(); i++) {131checksum_one += packet.payload[i];132checksum_two += checksum_one;133}134135return packet.checksum[0] == checksum_one && packet.checksum[1] == checksum_two;136}137138AP_MicroStrain::DescriptorSet AP_MicroStrain::handle_packet(const MicroStrain_Packet& packet)139{140const DescriptorSet descriptor = packet.descriptor_set();141switch (descriptor) {142case DescriptorSet::IMUData:143handle_imu(packet);144break;145case DescriptorSet::FilterData:146handle_filter(packet);147break;148case DescriptorSet::BaseCommand:149case DescriptorSet::DMCommand:150case DescriptorSet::SystemCommand:151break;152case DescriptorSet::GNSSData:153case DescriptorSet::GNSSRecv1:154case DescriptorSet::GNSSRecv2:155handle_gnss(packet);156break;157}158return descriptor;159}160161162void AP_MicroStrain::handle_imu(const MicroStrain_Packet& packet)163{164last_imu_pkt = AP_HAL::millis();165166// Iterate through fields of varying lengths in INS packet167for (uint8_t i = 0; i < packet.payload_length(); i += packet.payload[i]) {168switch ((INSPacketField) packet.payload[i+1]) {169// Scaled Ambient Pressure170case INSPacketField::PRESSURE: {171imu_data.pressure = be32tofloat_ptr(packet.payload, i+2) * 100; // Convert millibar to pascals172break;173}174// Scaled Magnetometer Vector175case INSPacketField::MAG: {176imu_data.mag = populate_vector3f(packet.payload, i+2) * 1000; // Convert gauss to milligauss177break;178}179// Scaled Accelerometer Vector180case INSPacketField::ACCEL: {181imu_data.accel = populate_vector3f(packet.payload, i+2) * GRAVITY_MSS; // Convert g's to m/s^2182break;183}184// Scaled Gyro Vector185case INSPacketField::GYRO: {186imu_data.gyro = populate_vector3f(packet.payload, i+2);187break;188}189// Quaternion190case INSPacketField::QUAT: {191imu_data.quat = populate_quaternion(packet.payload, i+2);192break;193}194}195}196}197198199void AP_MicroStrain::handle_gnss(const MicroStrain_Packet &packet)200{201last_gps_pkt = AP_HAL::millis();202uint8_t gnss_instance;203const DescriptorSet descriptor = DescriptorSet(packet.descriptor_set());204if (!get_gnss_instance(descriptor, gnss_instance)) {205return;206}207208// Iterate through fields of varying lengths in GNSS packet209for (uint8_t i = 0; i < packet.payload_length(); i += packet.payload[i]) {210switch ((GNSSPacketField) packet.payload[i+1]) {211case GNSSPacketField::GPS_TIMESTAMP: {212gnss_data[gnss_instance].tow_ms = double_to_uint32(be64todouble_ptr(packet.payload, i+2) * 1000); // Convert seconds to ms213gnss_data[gnss_instance].week = be16toh_ptr(&packet.payload[i+10]);214break;215}216case GNSSPacketField::FIX_INFO: {217switch ((GNSSFixType) packet.payload[i+2]) {218case (GNSSFixType::FIX_RTK_FLOAT): {219gnss_data[gnss_instance].fix_type = AP_GPS_FixType::RTK_FLOAT;220break;221}222case (GNSSFixType::FIX_RTK_FIXED): {223gnss_data[gnss_instance].fix_type = AP_GPS_FixType::RTK_FIXED;224break;225}226case (GNSSFixType::FIX_3D): {227gnss_data[gnss_instance].fix_type = AP_GPS_FixType::FIX_3D;228break;229}230case (GNSSFixType::FIX_2D): {231gnss_data[gnss_instance].fix_type = AP_GPS_FixType::FIX_2D;232break;233}234case (GNSSFixType::TIME_ONLY):235case (GNSSFixType::NONE): {236gnss_data[gnss_instance].fix_type = AP_GPS_FixType::NONE;237break;238}239default:240case (GNSSFixType::INVALID): {241gnss_data[gnss_instance].fix_type = AP_GPS_FixType::NO_GPS;242break;243}244}245246gnss_data[gnss_instance].satellites = packet.payload[i+3];247break;248}249case GNSSPacketField::LLH_POSITION: {250gnss_data[gnss_instance].lat = be64todouble_ptr(packet.payload, i+2) * 1.0e7; // Decimal degrees to degrees251gnss_data[gnss_instance].lon = be64todouble_ptr(packet.payload, i+10) * 1.0e7;252gnss_data[gnss_instance].msl_altitude = be64todouble_ptr(packet.payload, i+26) * 1.0e2; // Meters to cm253gnss_data[gnss_instance].horizontal_position_accuracy = be32tofloat_ptr(packet.payload, i+34);254gnss_data[gnss_instance].vertical_position_accuracy = be32tofloat_ptr(packet.payload, i+38);255break;256}257case GNSSPacketField::DOP_DATA: {258gnss_data[gnss_instance].hdop = be32tofloat_ptr(packet.payload, i+10);259gnss_data[gnss_instance].vdop = be32tofloat_ptr(packet.payload, i+14);260break;261}262case GNSSPacketField::NED_VELOCITY: {263gnss_data[gnss_instance].ned_velocity_north = be32tofloat_ptr(packet.payload, i+2);264gnss_data[gnss_instance].ned_velocity_east = be32tofloat_ptr(packet.payload, i+6);265gnss_data[gnss_instance].ned_velocity_down = be32tofloat_ptr(packet.payload, i+10);266gnss_data[gnss_instance].speed_accuracy = be32tofloat_ptr(packet.payload, i+26);267break;268}269}270}271}272273void AP_MicroStrain::handle_filter(const MicroStrain_Packet &packet)274{275last_filter_pkt = AP_HAL::millis();276277// Iterate through fields of varying lengths in filter packet278for (uint8_t i = 0; i < packet.payload_length(); i += packet.payload[i]) {279switch ((FilterPacketField) packet.payload[i+1]) {280case FilterPacketField::GPS_TIMESTAMP: {281filter_data.tow_ms = be64todouble_ptr(packet.payload, i+2) * 1000; // Convert seconds to ms282filter_data.week = be16toh_ptr(&packet.payload[i+10]);283break;284}285case FilterPacketField::LLH_POSITION: {286filter_data.lat = be64todouble_ptr(packet.payload, i+2) * 1.0e7; // Decimal degrees to degrees287filter_data.lon = be64todouble_ptr(packet.payload, i+10) * 1.0e7;288filter_data.hae_altitude = be64todouble_ptr(packet.payload, i+26) * 1.0e2; // Meters to cm289break;290}291case FilterPacketField::NED_VELOCITY: {292filter_data.ned_velocity_north = be32tofloat_ptr(packet.payload, i+2);293filter_data.ned_velocity_east = be32tofloat_ptr(packet.payload, i+6);294filter_data.ned_velocity_down = be32tofloat_ptr(packet.payload, i+10);295break;296}297case FilterPacketField::ATTITUDE_QUAT: {298filter_data.attitude_quat = populate_quaternion(packet.payload, i+2);299filter_data.attitude_quat.normalize();300break;301}302case FilterPacketField::LLH_POSITION_UNCERTAINTY: {303const float north_pos_acc = be32tofloat_ptr(packet.payload, i+2);304const float east_pos_acc = be32tofloat_ptr(packet.payload, i+6);305const float down_pos_acc = be32tofloat_ptr(packet.payload, i+10);306filter_data.ned_position_uncertainty = Vector3f(307north_pos_acc,308east_pos_acc,309down_pos_acc310);311break;312}313case FilterPacketField::NED_VELOCITY_UNCERTAINTY: {314const float north_vel_uncertainty = be32tofloat_ptr(packet.payload, i+2);315const float east_vel_uncertainty = be32tofloat_ptr(packet.payload, i+6);316const float down_vel_uncertainty = be32tofloat_ptr(packet.payload, i+10);317filter_data.ned_velocity_uncertainty = Vector3f(318north_vel_uncertainty,319east_vel_uncertainty,320down_vel_uncertainty321);322break;323}324case FilterPacketField::FILTER_STATUS: {325filter_status.state = be16toh_ptr(&packet.payload[i+2]);326filter_status.mode = be16toh_ptr(&packet.payload[i+4]);327filter_status.flags = be16toh_ptr(&packet.payload[i+6]);328break;329}330}331}332}333334Vector3f AP_MicroStrain::populate_vector3f(const uint8_t *data, uint8_t offset)335{336return Vector3f {337be32tofloat_ptr(data, offset),338be32tofloat_ptr(data, offset+4),339be32tofloat_ptr(data, offset+8)340};341}342343Quaternion AP_MicroStrain::populate_quaternion(const uint8_t *data, uint8_t offset)344{345// https://github.com/clemense/quaternion-conventions346// AP follows W + Xi + Yj + Zk format.347// Microstrain follows the same348return Quaternion {349be32tofloat_ptr(data, offset),350be32tofloat_ptr(data, offset+4),351be32tofloat_ptr(data, offset+8),352be32tofloat_ptr(data, offset+12)353};354}355356bool AP_MicroStrain::get_gnss_instance(const DescriptorSet& descriptor, uint8_t& instance){357bool success = false;358359switch(descriptor) {360case DescriptorSet::GNSSData:361case DescriptorSet::GNSSRecv1:362instance = 0;363success = true;364break;365case DescriptorSet::GNSSRecv2:366instance = 1;367success = true;368break;369default:370break;371}372return success;373}374375376377#endif // AP_MICROSTRAIN_ENABLED378379380