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_Compass/AP_Compass_SITL.cpp
Views: 1798
1
#include "AP_Compass_SITL.h"
2
3
#if AP_COMPASS_SITL_ENABLED
4
5
#include <AP_HAL/AP_HAL.h>
6
7
extern const AP_HAL::HAL& hal;
8
9
AP_Compass_SITL::AP_Compass_SITL()
10
: _sitl(AP::sitl())
11
{
12
if (_sitl != nullptr) {
13
for (uint8_t i=0; i<MAX_CONNECTED_MAGS; i++) {
14
uint32_t dev_id = _sitl->mag_devid[i];
15
if (dev_id == 0) {
16
continue;
17
}
18
uint8_t instance;
19
if (!register_compass(dev_id, instance)) {
20
continue;
21
} else if (_num_compass<MAX_SITL_COMPASSES) {
22
_compass_instance[_num_compass] = instance;
23
set_dev_id(_compass_instance[_num_compass], dev_id);
24
25
if (_sitl->mag_save_ids) {
26
// save so the compass always comes up configured in SITL
27
save_dev_id(_compass_instance[_num_compass]);
28
}
29
set_rotation(instance, ROTATION_NONE);
30
_num_compass++;
31
}
32
}
33
34
// Scroll through the registered compasses, and set the offsets
35
for (uint8_t i=0; i<_num_compass; i++) {
36
if (_compass.get_offsets(i).is_zero()) {
37
_compass.set_offsets(i, _sitl->mag_ofs[i]);
38
}
39
}
40
41
// we want to simulate a calibrated compass by default, so set
42
// scale to 1
43
AP_Param::set_default_by_name("COMPASS_SCALE", 1);
44
AP_Param::set_default_by_name("COMPASS_SCALE2", 1);
45
AP_Param::set_default_by_name("COMPASS_SCALE3", 1);
46
47
// make first compass external
48
set_external(_compass_instance[0], true);
49
50
hal.scheduler->register_timer_process(FUNCTOR_BIND(this, &AP_Compass_SITL::_timer, void));
51
}
52
}
53
54
55
/*
56
create correction matrix for diagonals and off-diagonals
57
*/
58
void AP_Compass_SITL::_setup_eliptical_correcion(uint8_t i)
59
{
60
Vector3f diag = _sitl->mag_diag[i].get();
61
if (diag.is_zero()) {
62
diag = {1,1,1};
63
}
64
const Vector3f &diagonals = diag;
65
const Vector3f &offdiagonals = _sitl->mag_offdiag[i];
66
67
if (diagonals == _last_dia && offdiagonals == _last_odi) {
68
return;
69
}
70
71
_eliptical_corr = Matrix3f(diagonals.x, offdiagonals.x, offdiagonals.y,
72
offdiagonals.x, diagonals.y, offdiagonals.z,
73
offdiagonals.y, offdiagonals.z, diagonals.z);
74
if (!_eliptical_corr.invert()) {
75
_eliptical_corr.identity();
76
}
77
_last_dia = diag;
78
_last_odi = offdiagonals;
79
}
80
81
void AP_Compass_SITL::_timer()
82
{
83
// TODO: Refactor delay buffer with AP_Baro_SITL.
84
85
// Sampled at 100Hz
86
uint32_t now = AP_HAL::millis();
87
if ((now - _last_sample_time) < 10) {
88
return;
89
}
90
_last_sample_time = now;
91
92
// calculate sensor noise and add to 'truth' field in body frame
93
// units are milli-Gauss
94
Vector3f noise = rand_vec3f() * _sitl->mag_noise;
95
Vector3f new_mag_data = _sitl->state.bodyMagField + noise;
96
97
// add delay
98
uint32_t best_time_delta = 1000; // initialise large time representing buffer entry closest to current time - delay.
99
uint8_t best_index = 0; // initialise number representing the index of the entry in buffer closest to delay.
100
101
// storing data from sensor to buffer
102
if (now - last_store_time >= 10) { // store data every 10 ms.
103
last_store_time = now;
104
if (store_index > buffer_length-1) { // reset buffer index if index greater than size of buffer
105
store_index = 0;
106
}
107
buffer[store_index].data = new_mag_data; // add data to current index
108
buffer[store_index].time = last_store_time; // add time to current index
109
store_index = store_index + 1; // increment index
110
}
111
112
// return delayed measurement
113
uint32_t delayed_time = now - _sitl->mag_delay; // get time corresponding to delay
114
// find data corresponding to delayed time in buffer
115
for (uint8_t i=0; i<=buffer_length-1; i++) {
116
// find difference between delayed time and time stamp in buffer
117
uint32_t time_delta = abs((int32_t)(delayed_time - buffer[i].time));
118
// if this difference is smaller than last delta, store this time
119
if (time_delta < best_time_delta) {
120
best_index= i;
121
best_time_delta = time_delta;
122
}
123
}
124
if (best_time_delta < 1000) { // only output stored state if < 1 sec retrieval error
125
new_mag_data = buffer[best_index].data;
126
}
127
128
for (uint8_t i=0; i<_num_compass; i++) {
129
_setup_eliptical_correcion(i);
130
Vector3f f = (_eliptical_corr * new_mag_data) - _sitl->mag_ofs[i].get();
131
// rotate compass
132
f.rotate_inverse((enum Rotation)_sitl->mag_orient[i].get());
133
f.rotate(get_board_orientation());
134
// scale the compass to simulate sensor scale factor errors
135
f *= _sitl->mag_scaling[i];
136
137
switch (_sitl->mag_fail[i]) {
138
case 0:
139
accumulate_sample(f, _compass_instance[i], 10);
140
_last_data[i] = f;
141
break;
142
case 1:
143
// no data
144
break;
145
case 2:
146
// frozen compass
147
accumulate_sample(_last_data[i], _compass_instance[i], 10);
148
break;
149
}
150
}
151
}
152
153
void AP_Compass_SITL::read()
154
{
155
for (uint8_t i=0; i<_num_compass; i++) {
156
drain_accumulated_samples(_compass_instance[i], nullptr);
157
}
158
}
159
#endif // AP_COMPASS_SITL_ENABLED
160
161