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