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_DAL/AP_DAL.cpp
Views: 1798
1
#include "AP_DAL.h"
2
3
#include <AP_HAL/AP_HAL.h>
4
#include <AP_Logger/AP_Logger.h>
5
#include <AP_AHRS/AP_AHRS.h>
6
#include <AP_Vehicle/AP_Vehicle.h>
7
#include <AP_OpticalFlow/AP_OpticalFlow.h>
8
#include <AP_WheelEncoder/AP_WheelEncoder.h>
9
#include <AP_Vehicle/AP_Vehicle_Type.h>
10
#include <AP_NavEKF3/AP_NavEKF3_feature.h>
11
#include <AP_NavEKF/AP_Nav_Common.h>
12
13
#if APM_BUILD_TYPE(APM_BUILD_Replay)
14
#include <AP_NavEKF2/AP_NavEKF2.h>
15
#include <AP_NavEKF3/AP_NavEKF3.h>
16
#endif
17
18
extern const AP_HAL::HAL& hal;
19
20
AP_DAL *AP_DAL::_singleton = nullptr;
21
22
bool AP_DAL::force_write;
23
bool AP_DAL::logging_started;
24
25
void AP_DAL::start_frame(AP_DAL::FrameType frametype)
26
{
27
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
28
29
if (!init_done) {
30
init_sensors();
31
}
32
33
const AP_AHRS &ahrs = AP::ahrs();
34
35
const uint32_t imu_us = AP::ins().get_last_update_usec();
36
if (_last_imu_time_us == imu_us) {
37
_RFRF.frame_types |= uint8_t(frametype);
38
return;
39
}
40
_last_imu_time_us = imu_us;
41
42
// we force write all msgs when logging starts
43
#if HAL_LOGGING_ENABLED
44
bool logging = AP::logger().logging_started() && AP::logger().allow_start_ekf();
45
if (logging && !logging_started) {
46
force_write = true;
47
}
48
logging_started = logging;
49
#endif
50
51
end_frame();
52
53
_RFRF.frame_types = uint8_t(frametype);
54
55
#if AP_VEHICLE_ENABLED
56
_RFRH.time_flying_ms = AP::vehicle()->get_time_flying_ms();
57
#else
58
_RFRH.time_flying_ms = 0;
59
#endif
60
_RFRH.time_us = AP_HAL::micros64();
61
WRITE_REPLAY_BLOCK(RFRH, _RFRH);
62
63
// update RFRN data
64
const log_RFRN old = _RFRN;
65
_RFRN.armed = hal.util->get_soft_armed();
66
_home = ahrs.get_home();
67
_RFRN.lat = _home.lat;
68
_RFRN.lng = _home.lng;
69
_RFRN.alt = _home.alt;
70
_RFRN.EAS2TAS = ahrs.get_EAS2TAS();
71
_RFRN.vehicle_class = (uint8_t)ahrs.get_vehicle_class();
72
_RFRN.fly_forward = ahrs.get_fly_forward();
73
_RFRN.takeoff_expected = ahrs.get_takeoff_expected();
74
_RFRN.touchdown_expected = ahrs.get_touchdown_expected();
75
_RFRN.ahrs_airspeed_sensor_enabled = ahrs.airspeed_sensor_enabled(ahrs.get_active_airspeed_index());
76
_RFRN.available_memory = hal.util->available_memory();
77
_RFRN.ahrs_trim = ahrs.get_trim();
78
#if AP_OPTICALFLOW_ENABLED
79
_RFRN.opticalflow_enabled = AP::opticalflow() && AP::opticalflow()->enabled();
80
#endif
81
_RFRN.wheelencoder_enabled = AP::wheelencoder() && (AP::wheelencoder()->num_sensors() > 0);
82
_RFRN.ekf_type = ahrs.get_ekf_type();
83
WRITE_REPLAY_BLOCK_IFCHANGED(RFRN, _RFRN, old);
84
85
// update body conversion
86
_rotation_vehicle_body_to_autopilot_body = ahrs.get_rotation_vehicle_body_to_autopilot_body();
87
88
_ins.start_frame();
89
_baro.start_frame();
90
_gps.start_frame();
91
_compass.start_frame();
92
if (_airspeed) {
93
_airspeed->start_frame();
94
}
95
#if AP_RANGEFINDER_ENABLED
96
if (_rangefinder) {
97
_rangefinder->start_frame();
98
}
99
#endif
100
#if AP_BEACON_ENABLED
101
if (_beacon) {
102
_beacon->start_frame();
103
}
104
#endif
105
#if HAL_VISUALODOM_ENABLED
106
if (_visualodom) {
107
_visualodom->start_frame();
108
}
109
#endif
110
111
// populate some derivative values:
112
_micros = _RFRH.time_us;
113
_millis = _RFRH.time_us / 1000UL;
114
115
force_write = false;
116
#endif
117
}
118
119
// for EKF usage to enable takeoff expected to true
120
void AP_DAL::set_takeoff_expected()
121
{
122
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
123
AP_AHRS &ahrs = AP::ahrs();
124
ahrs.set_takeoff_expected(true);
125
#endif
126
}
127
128
/*
129
setup optional sensor backends
130
*/
131
void AP_DAL::init_sensors(void)
132
{
133
init_done = true;
134
bool alloc_failed = false;
135
136
/*
137
we only allocate the DAL backends if we had at least one sensor
138
at the time we startup the EKF
139
*/
140
141
#if AP_RANGEFINDER_ENABLED
142
auto *rng = AP::rangefinder();
143
if (rng && rng->num_sensors() > 0) {
144
alloc_failed |= (_rangefinder = NEW_NOTHROW AP_DAL_RangeFinder) == nullptr;
145
}
146
#endif
147
148
#if AP_AIRSPEED_ENABLED
149
auto *aspeed = AP::airspeed();
150
if (aspeed != nullptr && aspeed->get_num_sensors() > 0) {
151
alloc_failed |= (_airspeed = NEW_NOTHROW AP_DAL_Airspeed) == nullptr;
152
}
153
#endif
154
155
#if AP_BEACON_ENABLED
156
auto *bcn = AP::beacon();
157
if (bcn != nullptr && bcn->enabled()) {
158
alloc_failed |= (_beacon = NEW_NOTHROW AP_DAL_Beacon) == nullptr;
159
}
160
#endif
161
162
#if HAL_VISUALODOM_ENABLED
163
auto *vodom = AP::visualodom();
164
if (vodom != nullptr && vodom->enabled()) {
165
alloc_failed |= (_visualodom = NEW_NOTHROW AP_DAL_VisualOdom) == nullptr;
166
}
167
#endif
168
169
if (alloc_failed) {
170
AP_BoardConfig::allocation_error("DAL backends");
171
}
172
}
173
174
/*
175
end a frame. Must be called on all events and injections of data (eg
176
flow) and before starting a new frame
177
*/
178
void AP_DAL::end_frame(void)
179
{
180
if (_RFRF.frame_types != 0) {
181
WRITE_REPLAY_BLOCK(RFRF, _RFRF);
182
_RFRF.frame_types = 0;
183
}
184
}
185
186
void AP_DAL::log_event2(AP_DAL::Event event)
187
{
188
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
189
end_frame();
190
struct log_REV2 pkt{
191
event : uint8_t(event),
192
};
193
WRITE_REPLAY_BLOCK(REV2, pkt);
194
#endif
195
}
196
197
void AP_DAL::log_SetOriginLLH2(const Location &loc)
198
{
199
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
200
struct log_RSO2 pkt{
201
lat : loc.lat,
202
lng : loc.lng,
203
alt : loc.alt,
204
};
205
WRITE_REPLAY_BLOCK(RSO2, pkt);
206
#endif
207
}
208
209
void AP_DAL::log_writeDefaultAirSpeed2(const float aspeed, const float uncertainty)
210
{
211
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
212
struct log_RWA2 pkt{
213
airspeed: aspeed,
214
uncertainty: uncertainty,
215
};
216
WRITE_REPLAY_BLOCK(RWA2, pkt);
217
#endif
218
}
219
220
void AP_DAL::log_event3(AP_DAL::Event event)
221
{
222
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
223
end_frame();
224
struct log_REV3 pkt{
225
event : uint8_t(event),
226
};
227
WRITE_REPLAY_BLOCK(REV3, pkt);
228
#endif
229
}
230
231
void AP_DAL::log_SetOriginLLH3(const Location &loc)
232
{
233
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
234
struct log_RSO3 pkt{
235
lat : loc.lat,
236
lng : loc.lng,
237
alt : loc.alt,
238
};
239
WRITE_REPLAY_BLOCK(RSO3, pkt);
240
#endif
241
}
242
243
void AP_DAL::log_writeDefaultAirSpeed3(const float aspeed, const float uncertainty)
244
{
245
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
246
struct log_RWA3 pkt{
247
airspeed: aspeed,
248
uncertainty: uncertainty
249
};
250
WRITE_REPLAY_BLOCK(RWA3, pkt);
251
#endif
252
}
253
254
void AP_DAL::log_writeEulerYawAngle(float yawAngle, float yawAngleErr, uint32_t timeStamp_ms, uint8_t type)
255
{
256
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
257
struct log_REY3 pkt{
258
yawangle : yawAngle,
259
yawangleerr : yawAngleErr,
260
timestamp_ms : timeStamp_ms,
261
type : type,
262
};
263
WRITE_REPLAY_BLOCK(REY3, pkt);
264
#endif
265
}
266
267
int AP_DAL::snprintf(char* str, size_t size, const char *format, ...) const
268
{
269
va_list ap;
270
va_start(ap, format);
271
int res = hal.util->vsnprintf(str, size, format, ap);
272
va_end(ap);
273
return res;
274
}
275
276
void *AP_DAL::malloc_type(size_t size, MemoryType mem_type) const
277
{
278
return hal.util->malloc_type(size, AP_HAL::Util::Memory_Type(mem_type));
279
}
280
void AP_DAL::free_type(void *ptr, size_t size, MemoryType mem_type) const
281
{
282
return hal.util->free_type(ptr, size, AP_HAL::Util::Memory_Type(mem_type));
283
}
284
285
// map core number for replay
286
uint8_t AP_DAL::logging_core(uint8_t c) const
287
{
288
#if APM_BUILD_TYPE(APM_BUILD_Replay)
289
return c+100U;
290
#else
291
return c;
292
#endif
293
}
294
295
#if HAL_LOGGING_ENABLED
296
// write out a DAL log message. If old_msg is non-null, then
297
// only write if the content has changed
298
void AP_DAL::WriteLogMessage(enum LogMessages msg_type, void *msg, const void *old_msg, uint8_t msg_size)
299
{
300
if (!logging_started) {
301
// we're not logging
302
return;
303
}
304
// we use the _end byte to hold a flag for forcing output
305
uint8_t &_end = ((uint8_t *)msg)[msg_size];
306
if (old_msg && !force_write && _end == 0 && memcmp(msg, old_msg, msg_size) == 0) {
307
// no change, skip this block write
308
return;
309
}
310
if (!AP::logger().WriteReplayBlock(msg_type, msg, msg_size)) {
311
// mark for forced write next time
312
_end = 1;
313
} else {
314
_end = 0;
315
}
316
}
317
#endif
318
319
/*
320
check if we are low on CPU for this core. This needs to capture the
321
timing of running the cores
322
*/
323
bool AP_DAL::ekf_low_time_remaining(EKFType etype, uint8_t core)
324
{
325
static_assert(MAX_EKF_CORES <= 4, "max 4 EKF cores supported");
326
const uint8_t mask = (1U<<(core+(uint8_t(etype)*4)));
327
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
328
/*
329
if we have used more than 1/3 of the time for a loop then we
330
return true, indicating that we are low on CPU. This changes the
331
scheduling of fusion between lanes
332
*/
333
const auto &imu = AP::ins();
334
if ((AP_HAL::micros() - imu.get_last_update_usec())*1.0e-6 > imu.get_loop_delta_t()*0.33) {
335
_RFRF.core_slow |= mask;
336
} else {
337
_RFRF.core_slow &= ~mask;
338
}
339
#endif
340
return (_RFRF.core_slow & mask) != 0;
341
}
342
343
// log optical flow data
344
void AP_DAL::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset, float heightOverride)
345
{
346
end_frame();
347
348
const log_ROFH old = _ROFH;
349
_ROFH.rawFlowQuality = rawFlowQuality;
350
_ROFH.rawFlowRates = rawFlowRates;
351
_ROFH.rawGyroRates = rawGyroRates;
352
_ROFH.msecFlowMeas = msecFlowMeas;
353
_ROFH.posOffset = posOffset;
354
_ROFH.heightOverride = heightOverride;
355
WRITE_REPLAY_BLOCK_IFCHANGED(ROFH, _ROFH, old);
356
}
357
358
// log external navigation data
359
void AP_DAL::writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms)
360
{
361
end_frame();
362
363
const log_REPH old = _REPH;
364
_REPH.pos = pos;
365
_REPH.quat = quat;
366
_REPH.posErr = posErr;
367
_REPH.angErr = angErr;
368
_REPH.timeStamp_ms = timeStamp_ms;
369
_REPH.delay_ms = delay_ms;
370
_REPH.resetTime_ms = resetTime_ms;
371
WRITE_REPLAY_BLOCK_IFCHANGED(REPH, _REPH, old);
372
}
373
374
void AP_DAL::log_SetLatLng(const Location &loc, float posAccuracy, uint32_t timestamp_ms)
375
{
376
end_frame();
377
const log_RSLL old = _RSLL;
378
_RSLL.lat = loc.lat;
379
_RSLL.lng = loc.lng;
380
_RSLL.posAccSD = posAccuracy;
381
_RSLL.timestamp_ms = timestamp_ms;
382
WRITE_REPLAY_BLOCK_IFCHANGED(RSLL, _RSLL, old);
383
}
384
385
// log external velocity data
386
void AP_DAL::writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms)
387
{
388
end_frame();
389
390
const log_REVH old = _REVH;
391
_REVH.vel = vel;
392
_REVH.err = err;
393
_REVH.timeStamp_ms = timeStamp_ms;
394
_REVH.delay_ms = delay_ms;
395
WRITE_REPLAY_BLOCK_IFCHANGED(REVH, _REVH, old);
396
397
}
398
399
// log wheel odometry data
400
void AP_DAL::writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius)
401
{
402
end_frame();
403
404
const log_RWOH old = _RWOH;
405
_RWOH.delAng = delAng;
406
_RWOH.delTime = delTime;
407
_RWOH.timeStamp_ms = timeStamp_ms;
408
_RWOH.posOffset = posOffset;
409
_RWOH.radius = radius;
410
WRITE_REPLAY_BLOCK_IFCHANGED(RWOH, _RWOH, old);
411
}
412
413
void AP_DAL::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset)
414
{
415
end_frame();
416
417
const log_RBOH old = _RBOH;
418
_RBOH.quality = quality;
419
_RBOH.delPos = delPos;
420
_RBOH.delAng = delAng;
421
_RBOH.delTime = delTime;
422
_RBOH.timeStamp_ms = timeStamp_ms;
423
WRITE_REPLAY_BLOCK_IFCHANGED(RBOH, _RBOH, old);
424
}
425
426
#if APM_BUILD_TYPE(APM_BUILD_Replay)
427
/*
428
handle frame message. This message triggers the EKF2/EKF3 updates and logging
429
*/
430
void AP_DAL::handle_message(const log_RFRF &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)
431
{
432
_RFRF.core_slow = msg.core_slow;
433
434
/*
435
note that we need to handle the case of LOG_REPLAY=1 with
436
LOG_DISARMED=0. To handle this we need to record the start of the filter
437
*/
438
const uint8_t frame_types = msg.frame_types;
439
if (frame_types & uint8_t(AP_DAL::FrameType::InitialiseFilterEKF2)) {
440
ekf2_init_done = ekf2.InitialiseFilter();
441
}
442
if (frame_types & uint8_t(AP_DAL::FrameType::UpdateFilterEKF2)) {
443
if (!ekf2_init_done) {
444
ekf2_init_done = ekf2.InitialiseFilter();
445
}
446
if (ekf2_init_done) {
447
ekf2.UpdateFilter();
448
}
449
}
450
if (frame_types & uint8_t(AP_DAL::FrameType::InitialiseFilterEKF3)) {
451
ekf3_init_done = ekf3.InitialiseFilter();
452
}
453
if (frame_types & uint8_t(AP_DAL::FrameType::UpdateFilterEKF3)) {
454
if (!ekf3_init_done) {
455
ekf3_init_done = ekf3.InitialiseFilter();
456
}
457
if (ekf3_init_done) {
458
ekf3.UpdateFilter();
459
}
460
}
461
if (frame_types & uint8_t(AP_DAL::FrameType::LogWriteEKF2)) {
462
ekf2.Log_Write();
463
}
464
if (frame_types & uint8_t(AP_DAL::FrameType::LogWriteEKF3)) {
465
ekf3.Log_Write();
466
}
467
}
468
469
/*
470
handle optical flow message
471
*/
472
void AP_DAL::handle_message(const log_ROFH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)
473
{
474
_ROFH = msg;
475
ekf2.writeOptFlowMeas(msg.rawFlowQuality, msg.rawFlowRates, msg.rawGyroRates, msg.msecFlowMeas, msg.posOffset, msg.heightOverride);
476
#if EK3_FEATURE_OPTFLOW_FUSION
477
ekf3.writeOptFlowMeas(msg.rawFlowQuality, msg.rawFlowRates, msg.rawGyroRates, msg.msecFlowMeas, msg.posOffset, msg.heightOverride);
478
#endif
479
}
480
481
/*
482
handle external position data
483
*/
484
void AP_DAL::handle_message(const log_REPH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)
485
{
486
_REPH = msg;
487
ekf2.writeExtNavData(msg.pos, msg.quat, msg.posErr, msg.angErr, msg.timeStamp_ms, msg.delay_ms, msg.resetTime_ms);
488
ekf3.writeExtNavData(msg.pos, msg.quat, msg.posErr, msg.angErr, msg.timeStamp_ms, msg.delay_ms, msg.resetTime_ms);
489
}
490
491
/*
492
handle external velocity data
493
*/
494
void AP_DAL::handle_message(const log_REVH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)
495
{
496
_REVH = msg;
497
ekf2.writeExtNavVelData(msg.vel, msg.err, msg.timeStamp_ms, msg.delay_ms);
498
ekf3.writeExtNavVelData(msg.vel, msg.err, msg.timeStamp_ms, msg.delay_ms);
499
}
500
501
/*
502
handle wheel odometry data
503
*/
504
void AP_DAL::handle_message(const log_RWOH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)
505
{
506
_RWOH = msg;
507
// note that EKF2 does not support wheel odometry
508
ekf3.writeWheelOdom(msg.delAng, msg.delTime, msg.timeStamp_ms, msg.posOffset, msg.radius);
509
}
510
511
/*
512
handle body frame odometry
513
*/
514
void AP_DAL::handle_message(const log_RBOH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)
515
{
516
_RBOH = msg;
517
// note that EKF2 does not support body frame odometry
518
ekf3.writeBodyFrameOdom(msg.quality, msg.delPos, msg.delAng, msg.delTime, msg.timeStamp_ms, msg.delay_ms, msg.posOffset);
519
}
520
521
/*
522
handle position reset
523
*/
524
void AP_DAL::handle_message(const log_RSLL &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)
525
{
526
_RSLL = msg;
527
// note that EKF2 does not support body frame odometry
528
const Location loc {msg.lat, msg.lng, 0, Location::AltFrame::ABSOLUTE };
529
ekf3.setLatLng(loc, msg.posAccSD, msg.timestamp_ms);
530
}
531
#endif // APM_BUILD_Replay
532
533
namespace AP {
534
535
AP_DAL &dal()
536
{
537
return *AP_DAL::get_singleton();
538
}
539
540
};
541
542
/*
543
replay printf. To debug replay failures add rprintf() calls into
544
EKF2/EKF3 and compare /tmp/replay.log to /tmp/real.log
545
*/
546
void rprintf(const char *format, ...)
547
{
548
549
#if (APM_BUILD_TYPE(APM_BUILD_Replay) || CONFIG_HAL_BOARD == HAL_BOARD_SITL) && CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS
550
#if APM_BUILD_TYPE(APM_BUILD_Replay)
551
const char *fname = "/tmp/replay.log";
552
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
553
const char *fname = "/tmp/real.log";
554
#endif
555
static FILE *f;
556
if (!f) {
557
f = ::fopen(fname, "w");
558
}
559
va_list ap;
560
va_start(ap, format);
561
vfprintf(f, format, ap);
562
fflush(f);
563
va_end(ap);
564
#endif
565
}
566
567
568