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