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/AP_ExternalAHRS_MicroStrain7.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 GQ7 serially connected AHRS Systems
15
Usage in SITL with hardware for debugging:
16
$ sim_vehicle.py -v Plane -A "--serial3=uart:/dev/3dm-gq7" --console --map -DG
17
$ ./Tools/autotest/sim_vehicle.py -v Plane -A "--serial3=uart:/dev/3dm-gq7" -DG
18
param set AHRS_EKF_TYPE 11
19
param set EAHRS_TYPE 7
20
param set GPS1_TYPE 21
21
param set GPS2_TYPE 21
22
param set SERIAL3_BAUD 115
23
param set SERIAL3_PROTOCOL 36
24
UDEV rules for repeatable USB connection:
25
$ cat /etc/udev/rules.d/99-usb-serial.rules
26
SUBSYSTEM=="tty", ATTRS{manufacturer}=="Lord Microstrain", SYMLINK+="3dm-gq7"
27
Usage with simulated MicroStrain7:
28
./Tools/autotest/sim_vehicle.py -v Plane -A "--serial3=sim:MicroStrain7" --console --map -DG
29
*/
30
31
#define ALLOW_DOUBLE_MATH_FUNCTIONS
32
33
#include "AP_ExternalAHRS_config.h"
34
35
#if AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED
36
37
#include "AP_ExternalAHRS_MicroStrain7.h"
38
#include "AP_Compass/AP_Compass_config.h"
39
#include <AP_Baro/AP_Baro.h>
40
#include <AP_Compass/AP_Compass.h>
41
#include <AP_GPS/AP_GPS.h>
42
#include <AP_HAL/utility/sparse-endian.h>
43
#include <AP_InertialSensor/AP_InertialSensor.h>
44
#include <GCS_MAVLink/GCS.h>
45
#include <AP_Logger/AP_Logger.h>
46
#include <AP_BoardConfig/AP_BoardConfig.h>
47
#include <AP_SerialManager/AP_SerialManager.h>
48
49
static const char* LOG_FMT = "%s ExternalAHRS: %s";
50
51
extern const AP_HAL::HAL &hal;
52
53
AP_ExternalAHRS_MicroStrain7::AP_ExternalAHRS_MicroStrain7(AP_ExternalAHRS *_frontend,
54
AP_ExternalAHRS::state_t &_state): AP_ExternalAHRS_backend(_frontend, _state)
55
{
56
auto &sm = AP::serialmanager();
57
uart = sm.find_serial(AP_SerialManager::SerialProtocol_AHRS, 0);
58
59
baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0);
60
port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0);
61
62
if (!uart) {
63
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, LOG_FMT, get_name(), "no UART");
64
return;
65
}
66
67
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_MicroStrain7::update_thread, void), "AHRS", 2048, AP_HAL::Scheduler::PRIORITY_SPI, 0)) {
68
AP_BoardConfig::allocation_error("MicroStrain7 ExternalAHRS failed to allocate ExternalAHRS update thread");
69
}
70
71
// don't offer IMU by default, at 100Hz it is too slow for many aircraft
72
set_default_sensors(uint16_t(AP_ExternalAHRS::AvailableSensor::GPS) |
73
uint16_t(AP_ExternalAHRS::AvailableSensor::BARO) |
74
uint16_t(AP_ExternalAHRS::AvailableSensor::COMPASS));
75
76
hal.scheduler->delay(5000);
77
if (!initialised()) {
78
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, LOG_FMT, get_name(), "failed to initialise.");
79
}
80
}
81
82
void AP_ExternalAHRS_MicroStrain7::update_thread(void)
83
{
84
if (!port_open) {
85
port_open = true;
86
uart->begin(baudrate);
87
}
88
89
while (true) {
90
build_packet();
91
hal.scheduler->delay_microseconds(100);
92
check_initialise_state();
93
}
94
}
95
96
void AP_ExternalAHRS_MicroStrain7::check_initialise_state(void)
97
{
98
const auto new_init_state = initialised();
99
// Only send the message after fully booted up, otherwise it gets dropped.
100
if (!last_init_state && new_init_state && AP_HAL::millis() > 5000) {
101
GCS_SEND_TEXT(MAV_SEVERITY_INFO, LOG_FMT, get_name(), "initialised.");
102
last_init_state = new_init_state;
103
}
104
}
105
106
107
// Builds packets by looking at each individual byte, once a full packet has been read in it checks the checksum then handles the packet.
108
void AP_ExternalAHRS_MicroStrain7::build_packet()
109
{
110
if (uart == nullptr) {
111
return;
112
}
113
114
WITH_SEMAPHORE(sem);
115
uint32_t nbytes = MIN(uart->available(), 2048u);
116
while (nbytes--> 0) {
117
uint8_t b;
118
if (!uart->read(b)) {
119
break;
120
}
121
DescriptorSet descriptor;
122
if (handle_byte(b, descriptor)) {
123
switch (descriptor) {
124
case DescriptorSet::IMUData:
125
post_imu();
126
break;
127
case DescriptorSet::GNSSData:
128
case DescriptorSet::GNSSRecv1:
129
case DescriptorSet::GNSSRecv2:
130
break;
131
case DescriptorSet::FilterData:
132
post_filter();
133
break;
134
case DescriptorSet::BaseCommand:
135
case DescriptorSet::DMCommand:
136
case DescriptorSet::SystemCommand:
137
break;
138
}
139
}
140
}
141
}
142
143
144
145
// Posts data from an imu packet to `state` and `handle_external` methods
146
void AP_ExternalAHRS_MicroStrain7::post_imu() const
147
{
148
{
149
WITH_SEMAPHORE(state.sem);
150
state.accel = imu_data.accel;
151
state.gyro = imu_data.gyro;
152
}
153
154
{
155
// *INDENT-OFF*
156
AP_ExternalAHRS::ins_data_message_t ins {
157
accel: imu_data.accel,
158
gyro: imu_data.gyro,
159
temperature: -300
160
};
161
// *INDENT-ON*
162
AP::ins().handle_external(ins);
163
}
164
165
#if AP_COMPASS_EXTERNALAHRS_ENABLED
166
{
167
// *INDENT-OFF*
168
AP_ExternalAHRS::mag_data_message_t mag {
169
field: imu_data.mag
170
};
171
// *INDENT-ON*
172
AP::compass().handle_external(mag);
173
}
174
#endif
175
176
#if AP_BARO_EXTERNALAHRS_ENABLED
177
{
178
// *INDENT-OFF*
179
const AP_ExternalAHRS::baro_data_message_t baro {
180
instance: 0,
181
pressure_pa: imu_data.pressure,
182
// setting temp to 25 effectively disables barometer temperature calibrations - these are already performed by MicroStrain
183
temperature: 25,
184
};
185
// *INDENT-ON*
186
AP::baro().handle_external(baro);
187
}
188
#endif
189
}
190
191
void AP_ExternalAHRS_MicroStrain7::post_filter() const
192
{
193
{
194
WITH_SEMAPHORE(state.sem);
195
state.velocity = Vector3f{filter_data.ned_velocity_north, filter_data.ned_velocity_east, filter_data.ned_velocity_down};
196
state.have_velocity = true;
197
198
// TODO the filter does not supply MSL altitude.
199
// The GNSS system has both MSL and WGS-84 ellipsoid height.
200
// Use GNSS 0 even though it may be bad.
201
state.location = Location{filter_data.lat, filter_data.lon, gnss_data[0].msl_altitude, Location::AltFrame::ABSOLUTE};
202
state.have_location = true;
203
204
state.quat = filter_data.attitude_quat;
205
state.have_quaternion = true;
206
}
207
208
for (int instance = 0; instance < NUM_GNSS_INSTANCES; instance++) {
209
// *INDENT-OFF*
210
AP_ExternalAHRS::gps_data_message_t gps {
211
gps_week: filter_data.week,
212
ms_tow: filter_data.tow_ms,
213
fix_type: AP_GPS_FixType(gnss_data[instance].fix_type),
214
satellites_in_view: gnss_data[instance].satellites,
215
216
horizontal_pos_accuracy: gnss_data[instance].horizontal_position_accuracy,
217
vertical_pos_accuracy: gnss_data[instance].vertical_position_accuracy,
218
horizontal_vel_accuracy: gnss_data[instance].speed_accuracy,
219
220
hdop: gnss_data[instance].hdop,
221
vdop: gnss_data[instance].vdop,
222
223
longitude: gnss_data[instance].lon,
224
latitude: gnss_data[instance].lat,
225
msl_altitude: gnss_data[instance].msl_altitude,
226
227
ned_vel_north: gnss_data[instance].ned_velocity_north,
228
ned_vel_east: gnss_data[instance].ned_velocity_east,
229
ned_vel_down: gnss_data[instance].ned_velocity_down,
230
};
231
// *INDENT-ON*
232
233
if (gps.fix_type >= AP_GPS_FixType::FIX_3D && !state.have_origin) {
234
WITH_SEMAPHORE(state.sem);
235
state.origin = Location{int32_t(gnss_data[instance].lat),
236
int32_t(gnss_data[instance].lon),
237
int32_t(gnss_data[instance].msl_altitude),
238
Location::AltFrame::ABSOLUTE};
239
state.have_origin = true;
240
}
241
AP::gps().handle_external(gps, instance);
242
}
243
}
244
245
int8_t AP_ExternalAHRS_MicroStrain7::get_port(void) const
246
{
247
if (!uart) {
248
return -1;
249
}
250
return port_num;
251
};
252
253
// Get model/type name
254
const char* AP_ExternalAHRS_MicroStrain7::get_name() const
255
{
256
return "MicroStrain7";
257
}
258
259
bool AP_ExternalAHRS_MicroStrain7::healthy(void) const
260
{
261
return times_healthy() && filter_healthy();
262
}
263
264
bool AP_ExternalAHRS_MicroStrain7::initialised(void) const
265
{
266
const bool got_packets = last_imu_pkt != 0 && last_gps_pkt != 0 && last_filter_pkt != 0;
267
return got_packets;
268
}
269
270
bool AP_ExternalAHRS_MicroStrain7::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const
271
{
272
if (!initialised()) {
273
hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "not initialised");
274
return false;
275
}
276
if (!times_healthy()) {
277
hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "data is stale");
278
return false;
279
}
280
if (!filter_healthy()) {
281
hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "filter is unhealthy");
282
return false;
283
}
284
if (!healthy()) {
285
hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "unhealthy");
286
return false;
287
}
288
static_assert(NUM_GNSS_INSTANCES == 2, "This check only works if there are two GPS types.");
289
if (gnss_data[0].fix_type < GPS_FIX_TYPE_3D_FIX && gnss_data[1].fix_type < GPS_FIX_TYPE_3D_FIX) {
290
hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "missing 3D GPS fix on either GPS");
291
return false;
292
}
293
294
return true;
295
}
296
297
void AP_ExternalAHRS_MicroStrain7::get_filter_status(nav_filter_status &status) const
298
{
299
memset(&status, 0, sizeof(status));
300
if (last_imu_pkt != 0 && last_gps_pkt != 0) {
301
status.flags.initalized = true;
302
}
303
if (healthy() && last_imu_pkt != 0) {
304
status.flags.attitude = true;
305
status.flags.vert_vel = true;
306
status.flags.vert_pos = true;
307
308
const auto filter_state = static_cast<FilterState>(filter_status.state);
309
if (filter_state_healthy(filter_state)) {
310
status.flags.horiz_vel = true;
311
status.flags.horiz_pos_rel = true;
312
status.flags.horiz_pos_abs = true;
313
status.flags.pred_horiz_pos_rel = true;
314
status.flags.pred_horiz_pos_abs = true;
315
status.flags.using_gps = true;
316
}
317
}
318
}
319
320
// get variances
321
bool AP_ExternalAHRS_MicroStrain7::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const
322
{
323
velVar = filter_data.ned_velocity_uncertainty.length() * vel_gate_scale;
324
posVar = filter_data.ned_position_uncertainty.xy().length() * pos_gate_scale;
325
hgtVar = filter_data.ned_position_uncertainty.z * hgt_gate_scale;
326
tasVar = 0;
327
return true;
328
}
329
330
bool AP_ExternalAHRS_MicroStrain7::times_healthy() const
331
{
332
uint32_t now = AP_HAL::millis();
333
334
// Expect the following rates:
335
// * Navigation Filter: 25Hz = 40mS
336
// * GPS: 2Hz = 500mS
337
// * IMU: 25Hz = 40mS
338
339
// Allow for some slight variance of 10%
340
constexpr float RateFoS = 1.1;
341
342
constexpr uint32_t expected_filter_time_delta_ms = 40;
343
constexpr uint32_t expected_gps_time_delta_ms = 500;
344
constexpr uint32_t expected_imu_time_delta_ms = 40;
345
346
const bool times_healthy = (now - last_imu_pkt < expected_imu_time_delta_ms * RateFoS && \
347
now - last_gps_pkt < expected_gps_time_delta_ms * RateFoS && \
348
now - last_filter_pkt < expected_filter_time_delta_ms * RateFoS);
349
350
return times_healthy;
351
}
352
353
bool AP_ExternalAHRS_MicroStrain7::filter_healthy() const
354
{
355
const auto filter_state = static_cast<FilterState>(filter_status.state);
356
const bool filter_healthy = filter_state_healthy(filter_state);
357
return filter_healthy;
358
}
359
360
bool AP_ExternalAHRS_MicroStrain7::filter_state_healthy(FilterState state)
361
{
362
switch (state) {
363
case FilterState::GQ7_FULL_NAV:
364
case FilterState::GQ7_AHRS:
365
return true;
366
default:
367
return false;
368
}
369
}
370
371
#endif // AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED
372
373