CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_ExternalAHRS/MicroStrain_common.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
This program is distributed in the hope that it will be useful,
7
but WITHOUT ANY WARRANTY; without even the implied warranty of
8
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
9
GNU General Public License for more details.
10
You should have received a copy of the GNU General Public License
11
along with this program. If not, see <http://www.gnu.org/licenses/>.
12
*/
13
/*
14
support for MicroStrain MIP parsing
15
*/
16
17
#define ALLOW_DOUBLE_MATH_FUNCTIONS
18
19
#include "AP_ExternalAHRS_config.h"
20
21
#if AP_MICROSTRAIN_ENABLED
22
23
#include "MicroStrain_common.h"
24
#include <AP_HAL/utility/sparse-endian.h>
25
26
// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/sensor_data/sensor_data_links.htm
27
enum class INSPacketField {
28
ACCEL = 0x04,
29
GYRO = 0x05,
30
QUAT = 0x0A,
31
MAG = 0x06,
32
PRESSURE = 0x17,
33
};
34
35
// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/gnss_recv_1/gnss_recv_1_links.htm
36
enum class GNSSPacketField {
37
LLH_POSITION = 0x03,
38
NED_VELOCITY = 0x05,
39
DOP_DATA = 0x07,
40
FIX_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.htm
42
GPS_TIMESTAMP = 0xD3,
43
};
44
45
// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/gnss_recv_1/data/mip_field_gnss_fix_info.htm
46
enum class GNSSFixType {
47
FIX_3D = 0x00,
48
FIX_2D = 0x01,
49
TIME_ONLY = 0x02,
50
NONE = 0x03,
51
INVALID = 0x04,
52
FIX_RTK_FLOAT = 0x05,
53
FIX_RTK_FIXED = 0x06,
54
};
55
56
// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/filter_data/filter_data_links.htm
57
enum class FilterPacketField {
58
FILTER_STATUS = 0x10,
59
LLH_POSITION = 0x01,
60
NED_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.htm
62
ATTITUDE_QUAT = 0x03,
63
// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/0x82/data/0x08.htm
64
LLH_POSITION_UNCERTAINTY = 0x08,
65
// https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/0x82/data/0x09.htm
66
NED_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.htm
68
GPS_TIMESTAMP = 0xD3,
69
};
70
71
bool AP_MicroStrain::handle_byte(const uint8_t b, DescriptorSet& descriptor)
72
{
73
switch (message_in.state) {
74
case ParseState::WaitingFor_SyncOne:
75
if (b == SYNC_ONE) {
76
message_in.packet.header[0] = b;
77
message_in.state = ParseState::WaitingFor_SyncTwo;
78
}
79
break;
80
case ParseState::WaitingFor_SyncTwo:
81
if (b == SYNC_TWO) {
82
message_in.packet.header[1] = b;
83
message_in.state = ParseState::WaitingFor_Descriptor;
84
} else {
85
message_in.state = ParseState::WaitingFor_SyncOne;
86
}
87
break;
88
case ParseState::WaitingFor_Descriptor:
89
message_in.packet.descriptor_set(b);
90
message_in.state = ParseState::WaitingFor_PayloadLength;
91
break;
92
case ParseState::WaitingFor_PayloadLength:
93
message_in.packet.payload_length(b);
94
message_in.state = ParseState::WaitingFor_Data;
95
message_in.index = 0;
96
break;
97
case ParseState::WaitingFor_Data:
98
message_in.packet.payload[message_in.index++] = b;
99
if (message_in.index >= message_in.packet.payload_length()) {
100
message_in.state = ParseState::WaitingFor_Checksum;
101
message_in.index = 0;
102
}
103
break;
104
case ParseState::WaitingFor_Checksum:
105
message_in.packet.checksum[message_in.index++] = b;
106
if (message_in.index >= 2) {
107
message_in.state = ParseState::WaitingFor_SyncOne;
108
message_in.index = 0;
109
110
if (valid_packet(message_in.packet)) {
111
descriptor = handle_packet(message_in.packet);
112
return true;
113
}
114
}
115
break;
116
}
117
return false;
118
}
119
120
bool AP_MicroStrain::valid_packet(const MicroStrain_Packet & packet)
121
{
122
uint8_t checksum_one = 0;
123
uint8_t checksum_two = 0;
124
125
for (int i = 0; i < 4; i++) {
126
checksum_one += packet.header[i];
127
checksum_two += checksum_one;
128
}
129
130
for (int i = 0; i < packet.payload_length(); i++) {
131
checksum_one += packet.payload[i];
132
checksum_two += checksum_one;
133
}
134
135
return packet.checksum[0] == checksum_one && packet.checksum[1] == checksum_two;
136
}
137
138
AP_MicroStrain::DescriptorSet AP_MicroStrain::handle_packet(const MicroStrain_Packet& packet)
139
{
140
const DescriptorSet descriptor = packet.descriptor_set();
141
switch (descriptor) {
142
case DescriptorSet::IMUData:
143
handle_imu(packet);
144
break;
145
case DescriptorSet::FilterData:
146
handle_filter(packet);
147
break;
148
case DescriptorSet::BaseCommand:
149
case DescriptorSet::DMCommand:
150
case DescriptorSet::SystemCommand:
151
break;
152
case DescriptorSet::GNSSData:
153
case DescriptorSet::GNSSRecv1:
154
case DescriptorSet::GNSSRecv2:
155
handle_gnss(packet);
156
break;
157
}
158
return descriptor;
159
}
160
161
162
void AP_MicroStrain::handle_imu(const MicroStrain_Packet& packet)
163
{
164
last_imu_pkt = AP_HAL::millis();
165
166
// Iterate through fields of varying lengths in INS packet
167
for (uint8_t i = 0; i < packet.payload_length(); i += packet.payload[i]) {
168
switch ((INSPacketField) packet.payload[i+1]) {
169
// Scaled Ambient Pressure
170
case INSPacketField::PRESSURE: {
171
imu_data.pressure = be32tofloat_ptr(packet.payload, i+2) * 100; // Convert millibar to pascals
172
break;
173
}
174
// Scaled Magnetometer Vector
175
case INSPacketField::MAG: {
176
imu_data.mag = populate_vector3f(packet.payload, i+2) * 1000; // Convert gauss to milligauss
177
break;
178
}
179
// Scaled Accelerometer Vector
180
case INSPacketField::ACCEL: {
181
imu_data.accel = populate_vector3f(packet.payload, i+2) * GRAVITY_MSS; // Convert g's to m/s^2
182
break;
183
}
184
// Scaled Gyro Vector
185
case INSPacketField::GYRO: {
186
imu_data.gyro = populate_vector3f(packet.payload, i+2);
187
break;
188
}
189
// Quaternion
190
case INSPacketField::QUAT: {
191
imu_data.quat = populate_quaternion(packet.payload, i+2);
192
break;
193
}
194
}
195
}
196
}
197
198
199
void AP_MicroStrain::handle_gnss(const MicroStrain_Packet &packet)
200
{
201
last_gps_pkt = AP_HAL::millis();
202
uint8_t gnss_instance;
203
const DescriptorSet descriptor = DescriptorSet(packet.descriptor_set());
204
if (!get_gnss_instance(descriptor, gnss_instance)) {
205
return;
206
}
207
208
// Iterate through fields of varying lengths in GNSS packet
209
for (uint8_t i = 0; i < packet.payload_length(); i += packet.payload[i]) {
210
switch ((GNSSPacketField) packet.payload[i+1]) {
211
case GNSSPacketField::GPS_TIMESTAMP: {
212
gnss_data[gnss_instance].tow_ms = double_to_uint32(be64todouble_ptr(packet.payload, i+2) * 1000); // Convert seconds to ms
213
gnss_data[gnss_instance].week = be16toh_ptr(&packet.payload[i+10]);
214
break;
215
}
216
case GNSSPacketField::FIX_INFO: {
217
switch ((GNSSFixType) packet.payload[i+2]) {
218
case (GNSSFixType::FIX_RTK_FLOAT): {
219
gnss_data[gnss_instance].fix_type = GPS_FIX_TYPE_RTK_FLOAT;
220
break;
221
}
222
case (GNSSFixType::FIX_RTK_FIXED): {
223
gnss_data[gnss_instance].fix_type = GPS_FIX_TYPE_RTK_FIXED;
224
break;
225
}
226
case (GNSSFixType::FIX_3D): {
227
gnss_data[gnss_instance].fix_type = GPS_FIX_TYPE_3D_FIX;
228
break;
229
}
230
case (GNSSFixType::FIX_2D): {
231
gnss_data[gnss_instance].fix_type = GPS_FIX_TYPE_2D_FIX;
232
break;
233
}
234
case (GNSSFixType::TIME_ONLY):
235
case (GNSSFixType::NONE): {
236
gnss_data[gnss_instance].fix_type = GPS_FIX_TYPE_NO_FIX;
237
break;
238
}
239
default:
240
case (GNSSFixType::INVALID): {
241
gnss_data[gnss_instance].fix_type = GPS_FIX_TYPE_NO_GPS;
242
break;
243
}
244
}
245
246
gnss_data[gnss_instance].satellites = packet.payload[i+3];
247
break;
248
}
249
case GNSSPacketField::LLH_POSITION: {
250
gnss_data[gnss_instance].lat = be64todouble_ptr(packet.payload, i+2) * 1.0e7; // Decimal degrees to degrees
251
gnss_data[gnss_instance].lon = be64todouble_ptr(packet.payload, i+10) * 1.0e7;
252
gnss_data[gnss_instance].msl_altitude = be64todouble_ptr(packet.payload, i+26) * 1.0e2; // Meters to cm
253
gnss_data[gnss_instance].horizontal_position_accuracy = be32tofloat_ptr(packet.payload, i+34);
254
gnss_data[gnss_instance].vertical_position_accuracy = be32tofloat_ptr(packet.payload, i+38);
255
break;
256
}
257
case GNSSPacketField::DOP_DATA: {
258
gnss_data[gnss_instance].hdop = be32tofloat_ptr(packet.payload, i+10);
259
gnss_data[gnss_instance].vdop = be32tofloat_ptr(packet.payload, i+14);
260
break;
261
}
262
case GNSSPacketField::NED_VELOCITY: {
263
gnss_data[gnss_instance].ned_velocity_north = be32tofloat_ptr(packet.payload, i+2);
264
gnss_data[gnss_instance].ned_velocity_east = be32tofloat_ptr(packet.payload, i+6);
265
gnss_data[gnss_instance].ned_velocity_down = be32tofloat_ptr(packet.payload, i+10);
266
gnss_data[gnss_instance].speed_accuracy = be32tofloat_ptr(packet.payload, i+26);
267
break;
268
}
269
}
270
}
271
}
272
273
void AP_MicroStrain::handle_filter(const MicroStrain_Packet &packet)
274
{
275
last_filter_pkt = AP_HAL::millis();
276
277
// Iterate through fields of varying lengths in filter packet
278
for (uint8_t i = 0; i < packet.payload_length(); i += packet.payload[i]) {
279
switch ((FilterPacketField) packet.payload[i+1]) {
280
case FilterPacketField::GPS_TIMESTAMP: {
281
filter_data.tow_ms = be64todouble_ptr(packet.payload, i+2) * 1000; // Convert seconds to ms
282
filter_data.week = be16toh_ptr(&packet.payload[i+10]);
283
break;
284
}
285
case FilterPacketField::LLH_POSITION: {
286
filter_data.lat = be64todouble_ptr(packet.payload, i+2) * 1.0e7; // Decimal degrees to degrees
287
filter_data.lon = be64todouble_ptr(packet.payload, i+10) * 1.0e7;
288
filter_data.hae_altitude = be64todouble_ptr(packet.payload, i+26) * 1.0e2; // Meters to cm
289
break;
290
}
291
case FilterPacketField::NED_VELOCITY: {
292
filter_data.ned_velocity_north = be32tofloat_ptr(packet.payload, i+2);
293
filter_data.ned_velocity_east = be32tofloat_ptr(packet.payload, i+6);
294
filter_data.ned_velocity_down = be32tofloat_ptr(packet.payload, i+10);
295
break;
296
}
297
case FilterPacketField::ATTITUDE_QUAT: {
298
filter_data.attitude_quat = populate_quaternion(packet.payload, i+2);
299
filter_data.attitude_quat.normalize();
300
break;
301
}
302
case FilterPacketField::LLH_POSITION_UNCERTAINTY: {
303
const float north_pos_acc = be32tofloat_ptr(packet.payload, i+2);
304
const float east_pos_acc = be32tofloat_ptr(packet.payload, i+6);
305
const float down_pos_acc = be32tofloat_ptr(packet.payload, i+10);
306
filter_data.ned_position_uncertainty = Vector3f(
307
north_pos_acc,
308
east_pos_acc,
309
down_pos_acc
310
);
311
break;
312
}
313
case FilterPacketField::NED_VELOCITY_UNCERTAINTY: {
314
const float north_vel_uncertainty = be32tofloat_ptr(packet.payload, i+2);
315
const float east_vel_uncertainty = be32tofloat_ptr(packet.payload, i+6);
316
const float down_vel_uncertainty = be32tofloat_ptr(packet.payload, i+10);
317
filter_data.ned_velocity_uncertainty = Vector3f(
318
north_vel_uncertainty,
319
east_vel_uncertainty,
320
down_vel_uncertainty
321
);
322
break;
323
}
324
case FilterPacketField::FILTER_STATUS: {
325
filter_status.state = be16toh_ptr(&packet.payload[i+2]);
326
filter_status.mode = be16toh_ptr(&packet.payload[i+4]);
327
filter_status.flags = be16toh_ptr(&packet.payload[i+6]);
328
break;
329
}
330
}
331
}
332
}
333
334
Vector3f AP_MicroStrain::populate_vector3f(const uint8_t *data, uint8_t offset)
335
{
336
return Vector3f {
337
be32tofloat_ptr(data, offset),
338
be32tofloat_ptr(data, offset+4),
339
be32tofloat_ptr(data, offset+8)
340
};
341
}
342
343
Quaternion AP_MicroStrain::populate_quaternion(const uint8_t *data, uint8_t offset)
344
{
345
// https://github.com/clemense/quaternion-conventions
346
// AP follows W + Xi + Yj + Zk format.
347
// Microstrain follows the same
348
return Quaternion {
349
be32tofloat_ptr(data, offset),
350
be32tofloat_ptr(data, offset+4),
351
be32tofloat_ptr(data, offset+8),
352
be32tofloat_ptr(data, offset+12)
353
};
354
}
355
356
bool AP_MicroStrain::get_gnss_instance(const DescriptorSet& descriptor, uint8_t& instance){
357
bool success = false;
358
359
switch(descriptor) {
360
case DescriptorSet::GNSSData:
361
case DescriptorSet::GNSSRecv1:
362
instance = 0;
363
success = true;
364
break;
365
case DescriptorSet::GNSSRecv2:
366
instance = 1;
367
success = true;
368
break;
369
default:
370
break;
371
}
372
return success;
373
}
374
375
376
377
#endif // AP_MICROSTRAIN_ENABLED
378