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