Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp
9524 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
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
/*
16
support for serial connected AHRS systems
17
*/
18
19
#include "AP_ExternalAHRS_config.h"
20
21
#if AP_EXTERNAL_AHRS_ENABLED
22
23
#include "AP_ExternalAHRS.h"
24
#include "AP_ExternalAHRS_backend.h"
25
#include "AP_ExternalAHRS_VectorNav.h"
26
#include "AP_ExternalAHRS_MicroStrain5.h"
27
#include "AP_ExternalAHRS_MicroStrain7.h"
28
#include "AP_ExternalAHRS_InertialLabs.h"
29
#include "AP_ExternalAHRS_SBG.h"
30
31
#include <GCS_MAVLink/GCS.h>
32
#include <AP_AHRS/AP_AHRS.h>
33
#include <AP_GPS/AP_GPS.h>
34
#include <AP_Logger/AP_Logger.h>
35
36
extern const AP_HAL::HAL &hal;
37
38
AP_ExternalAHRS *AP_ExternalAHRS::_singleton;
39
40
// constructor
41
AP_ExternalAHRS::AP_ExternalAHRS()
42
{
43
AP_Param::setup_object_defaults(this, var_info);
44
_singleton = this;
45
if (rate.get() < 50) {
46
// min 50Hz
47
rate.set(50);
48
}
49
}
50
51
#ifndef HAL_EXTERNAL_AHRS_DEFAULT
52
#define HAL_EXTERNAL_AHRS_DEFAULT 0
53
#endif
54
55
56
// table of user settable parameters
57
const AP_Param::GroupInfo AP_ExternalAHRS::var_info[] = {
58
59
// @Param: _TYPE
60
// @DisplayName: AHRS type
61
// @Description: Type of AHRS device
62
// @Values: 0:None,1:VectorNav,2:MicroStrain5,5:InertialLabs,7:MicroStrain7,8:SBG
63
// @User: Standard
64
AP_GROUPINFO_FLAGS("_TYPE", 1, AP_ExternalAHRS, devtype, HAL_EXTERNAL_AHRS_DEFAULT, AP_PARAM_FLAG_ENABLE),
65
66
// @Param: _RATE
67
// @DisplayName: AHRS data rate
68
// @Description: Requested rate for AHRS device
69
// @Units: Hz
70
// @User: Standard
71
AP_GROUPINFO("_RATE", 2, AP_ExternalAHRS, rate, 50),
72
73
// @Param: _OPTIONS
74
// @DisplayName: External AHRS options
75
// @Description: External AHRS options bitmask
76
// @Bitmask: 0:Vector Nav use uncompensated values for accel gyro and mag.
77
// @Bitmask: 1:SBG uses EKF as GNSS.
78
// @User: Standard
79
AP_GROUPINFO("_OPTIONS", 3, AP_ExternalAHRS, options, 0),
80
81
// @Param: _SENSORS
82
// @DisplayName: External AHRS sensors
83
// @Description: External AHRS sensors bitmask
84
// @Bitmask: 0:GPS,1:IMU,2:Baro,3:Compass
85
// @User: Advanced
86
AP_GROUPINFO("_SENSORS", 4, AP_ExternalAHRS, sensors, 0xF),
87
88
// @Param: _LOG_RATE
89
// @DisplayName: AHRS logging rate
90
// @Description: Logging rate for EAHRS devices
91
// @Units: Hz
92
// @User: Standard
93
AP_GROUPINFO("_LOG_RATE", 5, AP_ExternalAHRS, log_rate, 10),
94
95
AP_GROUPEND
96
};
97
98
99
void AP_ExternalAHRS::init(void)
100
{
101
if (rate.get() < 50) {
102
// min 50Hz
103
rate.set(50);
104
}
105
106
switch (DevType(devtype)) {
107
case DevType::None:
108
// nothing to do
109
return;
110
111
#if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
112
case DevType::VecNav:
113
backend = NEW_NOTHROW AP_ExternalAHRS_VectorNav(this, state);
114
return;
115
#endif
116
117
#if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED
118
case DevType::MicroStrain5:
119
backend = NEW_NOTHROW AP_ExternalAHRS_MicroStrain5(this, state);
120
return;
121
#endif
122
123
#if AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED
124
case DevType::MicroStrain7:
125
backend = NEW_NOTHROW AP_ExternalAHRS_MicroStrain7(this, state);
126
return;
127
#endif
128
129
#if AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED
130
case DevType::InertialLabs:
131
backend = NEW_NOTHROW AP_ExternalAHRS_InertialLabs(this, state);
132
return;
133
#endif
134
135
#if AP_EXTERNAL_AHRS_SBG_ENABLED
136
case DevType::SBG:
137
backend = NEW_NOTHROW AP_ExternalAHRS_SBG(this, state);
138
return;
139
#endif // AP_EXTERNAL_AHRS_SBG_ENABLED
140
141
}
142
143
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unsupported ExternalAHRS type %u", unsigned(devtype));
144
}
145
146
bool AP_ExternalAHRS::enabled() const
147
{
148
return DevType(devtype) != DevType::None;
149
}
150
151
// get serial port number for the uart, or -1 if not applicable
152
int8_t AP_ExternalAHRS::get_port(AvailableSensor sensor) const
153
{
154
if (!backend || !has_sensor(sensor)) {
155
return -1;
156
}
157
return backend->get_port();
158
};
159
160
// accessors for AP_AHRS
161
bool AP_ExternalAHRS::healthy(void) const
162
{
163
return backend && backend->healthy();
164
}
165
166
bool AP_ExternalAHRS::initialised(void) const
167
{
168
return backend && backend->initialised();
169
}
170
171
bool AP_ExternalAHRS::get_quaternion(Quaternion &quat)
172
{
173
if (state.have_quaternion) {
174
WITH_SEMAPHORE(state.sem);
175
quat = state.quat;
176
return true;
177
}
178
return false;
179
}
180
181
bool AP_ExternalAHRS::get_origin(Location &loc)
182
{
183
if (state.have_origin) {
184
WITH_SEMAPHORE(state.sem);
185
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
186
if (!state.origin.initialised()) {
187
AP_HAL::panic("Uninitialized origin in AP_ExternalAHRS.");
188
}
189
#endif
190
loc = state.origin;
191
return true;
192
}
193
return false;
194
}
195
196
bool AP_ExternalAHRS::set_origin(const Location &loc)
197
{
198
WITH_SEMAPHORE(state.sem);
199
if (state.have_origin) {
200
return false;
201
}
202
state.origin = loc;
203
state.have_origin = true;
204
return true;
205
}
206
207
bool AP_ExternalAHRS::get_location(Location &loc)
208
{
209
if (!state.have_location) {
210
return false;
211
}
212
WITH_SEMAPHORE(state.sem);
213
loc = state.location;
214
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
215
if (!loc.initialised()) {
216
AP_HAL::panic("Uninitialized location in AP_ExternalAHRS.");
217
}
218
#endif
219
220
if (state.last_location_update_us != 0 &&
221
state.have_velocity) {
222
// extrapolate position based on velocity to cope with slow backends
223
const float dt = (AP_HAL::micros() - state.last_location_update_us)*1.0e-6;
224
if (dt < 1) {
225
// only extrapolate for 1s max
226
Vector3p ofs = state.velocity.topostype();
227
ofs *= dt;
228
loc.offset(ofs);
229
}
230
}
231
232
return true;
233
}
234
235
Vector2f AP_ExternalAHRS::get_groundspeed_vector()
236
{
237
WITH_SEMAPHORE(state.sem);
238
Vector2f vec{state.velocity.x, state.velocity.y};
239
return vec;
240
}
241
242
bool AP_ExternalAHRS::get_velocity_NED(Vector3f &vel)
243
{
244
if (!state.have_velocity) {
245
return false;
246
}
247
WITH_SEMAPHORE(state.sem);
248
vel = state.velocity;
249
return true;
250
}
251
252
bool AP_ExternalAHRS::get_speed_down(float &speedD)
253
{
254
if (!state.have_velocity) {
255
return false;
256
}
257
WITH_SEMAPHORE(state.sem);
258
speedD = state.velocity.z;
259
return true;
260
}
261
262
bool AP_ExternalAHRS::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const
263
{
264
if (backend == nullptr) {
265
hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: Invalid backend");
266
return false;
267
}
268
if (!backend->pre_arm_check(failure_msg, failure_msg_len)) {
269
return false;
270
}
271
// Verify the user has configured the GPS to accept EAHRS data.
272
if (has_sensor(AvailableSensor::GPS)) {
273
const auto eahrs_gps_sensors = backend->num_gps_sensors();
274
275
const auto &gps = AP::gps();
276
uint8_t n_configured_eahrs_gps = 0;
277
for (uint8_t i = 0; i < GPS_MAX_INSTANCES; ++i) {
278
const auto gps_type = gps.get_type(i);
279
if (gps_type == AP_GPS::GPS_TYPE_EXTERNAL_AHRS) {
280
n_configured_eahrs_gps++;
281
}
282
}
283
284
// Once AP supports at least 3 GPS's, change to == and remove the second condition.
285
// At that point, enforce that all GPS's in EAHRS can report to AP_GPS.
286
if (n_configured_eahrs_gps < 1 && eahrs_gps_sensors >= 1) {
287
hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: Incorrect number of GPS sensors configured for EAHRS");
288
return false;
289
}
290
}
291
AP_AHRS &ahrs = AP::ahrs();
292
if (ahrs.configured_ekf_type() == AP_AHRS::EKFType::EXTERNAL) {
293
// when using EAHRS as the EKF source, we must have a valid position origin
294
if (!state.have_origin) {
295
hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: No origin");
296
return false;
297
}
298
}
299
return true;
300
}
301
302
/*
303
get filter status
304
*/
305
void AP_ExternalAHRS::get_filter_status(nav_filter_status &status) const
306
{
307
status = {};
308
if (backend) {
309
backend->get_filter_status(status);
310
}
311
}
312
313
/*
314
get estimated variances, return false if not implemented
315
*/
316
bool AP_ExternalAHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const
317
{
318
if (backend != nullptr) {
319
return backend->get_variances(velVar, posVar, hgtVar, magVar, tasVar);
320
}
321
return false;
322
}
323
324
bool AP_ExternalAHRS::get_gyro(Vector3f &gyro)
325
{
326
WITH_SEMAPHORE(state.sem);
327
if (!has_sensor(AvailableSensor::IMU)) {
328
return false;
329
}
330
gyro = state.gyro;
331
return true;
332
}
333
334
bool AP_ExternalAHRS::get_accel(Vector3f &accel)
335
{
336
WITH_SEMAPHORE(state.sem);
337
if (!has_sensor(AvailableSensor::IMU)) {
338
return false;
339
}
340
accel = state.accel;
341
return true;
342
}
343
344
// send an EKF_STATUS message to GCS
345
void AP_ExternalAHRS::send_status_report(GCS_MAVLINK &link) const
346
{
347
float velVar, posVar, hgtVar, tasVar;
348
Vector3f magVar;
349
if (backend == nullptr || !backend->get_variances(velVar, posVar, hgtVar, magVar, tasVar)) {
350
return;
351
}
352
353
uint16_t flags = 0;
354
nav_filter_status filterStatus {};
355
get_filter_status(filterStatus);
356
357
if (filterStatus.flags.attitude) {
358
flags |= EKF_ATTITUDE;
359
}
360
if (filterStatus.flags.horiz_vel) {
361
flags |= EKF_VELOCITY_HORIZ;
362
}
363
if (filterStatus.flags.vert_vel) {
364
flags |= EKF_VELOCITY_VERT;
365
}
366
if (filterStatus.flags.horiz_pos_rel) {
367
flags |= EKF_POS_HORIZ_REL;
368
}
369
if (filterStatus.flags.horiz_pos_abs) {
370
flags |= EKF_POS_HORIZ_ABS;
371
}
372
if (filterStatus.flags.vert_pos) {
373
flags |= EKF_POS_VERT_ABS;
374
}
375
if (filterStatus.flags.terrain_alt) {
376
flags |= EKF_POS_VERT_AGL;
377
}
378
if (filterStatus.flags.const_pos_mode) {
379
flags |= EKF_CONST_POS_MODE;
380
}
381
if (filterStatus.flags.pred_horiz_pos_rel) {
382
flags |= EKF_PRED_POS_HORIZ_REL;
383
}
384
if (filterStatus.flags.pred_horiz_pos_abs) {
385
flags |= EKF_PRED_POS_HORIZ_ABS;
386
}
387
if (!filterStatus.flags.initalized) {
388
flags |= EKF_UNINITIALIZED;
389
}
390
391
const float mag_var = MAX(magVar.x, MAX(magVar.y, magVar.z));
392
mavlink_msg_ekf_status_report_send(link.get_chan(), flags,
393
velVar,
394
posVar,
395
hgtVar,
396
mag_var, 0, 0);
397
}
398
399
void AP_ExternalAHRS::update(void)
400
{
401
if (backend) {
402
backend->update();
403
}
404
405
WITH_SEMAPHORE(state.sem);
406
#if HAL_LOGGING_ENABLED
407
const uint32_t now_ms = AP_HAL::millis();
408
if (enabled() && log_rate.get() > 0 && now_ms - last_log_ms >= uint32_t(1000U/log_rate.get())) {
409
last_log_ms = now_ms;
410
411
// @LoggerMessage: EAHR
412
// @Description: External AHRS data
413
// @Field: TimeUS: Time since system startup
414
// @Field: Roll: euler roll
415
// @Field: Pitch: euler pitch
416
// @Field: Yaw: euler yaw
417
// @Field: VN: velocity north
418
// @Field: VE: velocity east
419
// @Field: VD: velocity down
420
// @Field: Lat: latitude
421
// @Field: Lon: longitude
422
// @Field: Alt: altitude AMSL
423
// @Field: Flg: nav status flags
424
425
float roll, pitch, yaw;
426
state.quat.to_euler(roll, pitch, yaw);
427
nav_filter_status filterStatus {};
428
get_filter_status(filterStatus);
429
430
AP::logger().WriteStreaming("EAHR", "TimeUS,Roll,Pitch,Yaw,VN,VE,VD,Lat,Lon,Alt,Flg",
431
"sdddnnnDUm-",
432
"F000000GG0-",
433
"QffffffLLfI",
434
AP_HAL::micros64(),
435
degrees(roll), degrees(pitch), degrees(yaw),
436
state.velocity.x, state.velocity.y, state.velocity.z,
437
state.location.lat, state.location.lng, state.location.alt*0.01,
438
filterStatus.value);
439
440
// @LoggerMessage: EAHV
441
// @Description: External AHRS variances
442
// @Field: TimeUS: Time since system startup
443
// @Field: Vel: velocity variance
444
// @Field: Pos: position variance
445
// @Field: Hgt: height variance
446
// @Field: MagX: magnetic variance, X
447
// @Field: MagY: magnetic variance, Y
448
// @Field: MagZ: magnetic variance, Z
449
// @Field: TAS: true airspeed variance
450
451
float velVar, posVar, hgtVar, tasVar;
452
Vector3f magVar;
453
if (backend != nullptr && backend->get_variances(velVar, posVar, hgtVar, magVar, tasVar)) {
454
AP::logger().WriteStreaming("EAHV", "TimeUS,Vel,Pos,Hgt,MagX,MagY,MagZ,TAS",
455
"Qfffffff",
456
AP_HAL::micros64(),
457
velVar, posVar, hgtVar,
458
magVar.x, magVar.y, magVar.z,
459
tasVar);
460
}
461
}
462
#endif // HAL_LOGGING_ENABLED
463
}
464
465
// Get model/type name
466
const char* AP_ExternalAHRS::get_name() const
467
{
468
if (backend) {
469
return backend->get_name();
470
}
471
return nullptr;
472
}
473
474
namespace AP {
475
476
AP_ExternalAHRS &externalAHRS()
477
{
478
return *AP_ExternalAHRS::get_singleton();
479
}
480
481
};
482
483
#endif // AP_EXTERNAL_AHRS_ENABLED
484
485
486