APM:Libraries
AP_Compass_SITL.cpp
Go to the documentation of this file.
1 #include "AP_Compass_SITL.h"
2 
3 #include <AP_HAL/AP_HAL.h>
4 
5 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
6 extern const AP_HAL::HAL& hal;
7 
9  _has_sample(false),
10  AP_Compass_Backend(compass)
11 {
13  if (_sitl != nullptr) {
15  for (uint8_t i=0; i<SITL_NUM_COMPASSES; i++) {
17  }
19  }
20 }
21 
23 {
24  // TODO: Refactor delay buffer with AP_Baro_SITL.
25 
26  // Sampled at 100Hz
27  uint32_t now = AP_HAL::millis();
28  if ((now - _last_sample_time) < 10) {
29  return;
30  }
31  _last_sample_time = now;
32 
33  // calculate sensor noise and add to 'truth' field in body frame
34  // units are milli-Gauss
36  Vector3f new_mag_data = _sitl->state.bodyMagField + noise;
37 
38  // add delay
39  uint32_t best_time_delta = 1000; // initialise large time representing buffer entry closest to current time - delay.
40  uint8_t best_index = 0; // initialise number representing the index of the entry in buffer closest to delay.
41 
42  // storing data from sensor to buffer
43  if (now - last_store_time >= 10) { // store data every 10 ms.
44  last_store_time = now;
45  if (store_index > buffer_length-1) { // reset buffer index if index greater than size of buffer
46  store_index = 0;
47  }
48  buffer[store_index].data = new_mag_data; // add data to current index
49  buffer[store_index].time = last_store_time; // add time to current index
50  store_index = store_index + 1; // increment index
51  }
52 
53  // return delayed measurement
54  uint32_t delayed_time = now - _sitl->mag_delay; // get time corresponding to delay
55  // find data corresponding to delayed time in buffer
56  for (uint8_t i=0; i<=buffer_length-1; i++) {
57  // find difference between delayed time and time stamp in buffer
58  uint32_t time_delta = abs((int32_t)(delayed_time - buffer[i].time));
59  // if this difference is smaller than last delta, store this time
60  if (time_delta < best_time_delta) {
61  best_index= i;
62  best_time_delta = time_delta;
63  }
64  }
65  if (best_time_delta < 1000) { // only output stored state if < 1 sec retrieval error
66  new_mag_data = buffer[best_index].data;
67  }
68 
69  new_mag_data -= _sitl->mag_ofs.get();
70 
71  for (uint8_t i=0; i<SITL_NUM_COMPASSES; i++) {
72  rotate_field(new_mag_data, _compass_instance[i]);
73  publish_raw_field(new_mag_data, _compass_instance[i]);
74  correct_field(new_mag_data, _compass_instance[i]);
75  }
76 
78  return;
79  }
80 
81  _mag_accum += new_mag_data;
82  _accum_count++;
83  if (_accum_count == 10) {
84  _mag_accum /= 2;
85  _accum_count = 5;
86  _has_sample = true;
87  }
88  _sem->give();
89 }
90 
92 {
93  if (_sem->take_nonblocking()) {
94  if (!_has_sample) {
95  _sem->give();
96  return;
97  }
98 
99  Vector3f field(_mag_accum);
100  field /= _accum_count;
101  _mag_accum.zero();
102  _accum_count = 0;
103 
104  for (uint8_t i=0; i<SITL_NUM_COMPASSES; i++) {
106  }
107 
108  _has_sample = false;
109  _sem->give();
110  }
111 
112 }
113 #endif
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
VectorN< readings_compass, buffer_length > buffer
Vector3f bodyMagField
Definition: SITL.h:30
void rotate_field(Vector3f &mag, uint8_t instance)
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
void correct_field(Vector3f &mag, uint8_t i)
AP_Float mag_noise
Definition: SITL.h:107
uint32_t last_store_time
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
SITL::SITL * _sitl
void _setup_earth_field()
#define FUNCTOR_BIND(obj, func, rettype,...)
Definition: functor.h:28
virtual bool take_nonblocking() WARN_IF_UNUSED=0
uint8_t register_compass(void) const
static const uint8_t buffer_length
uint32_t millis()
Definition: system.cpp:157
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
uint8_t _compass_instance[SITL_NUM_COMPASSES]
virtual bool give()=0
static Compass compass
Definition: AHRS_Test.cpp:20
AP_HAL::Semaphore * _sem
virtual void register_timer_process(AP_HAL::MemberProc)=0
Vector3f rand_vec3f(void)
Definition: AP_Math.cpp:229
#define SITL_NUM_COMPASSES
void publish_raw_field(const Vector3f &mag, uint8_t instance)
uint32_t _accum_count
AP_Int16 mag_delay
Definition: SITL.h:164
uint32_t _last_sample_time
static float noise(void)
Definition: Derivative.cpp:21
AP_Vector3f mag_ofs
Definition: SITL.h:110
struct sitl_fdm state
Definition: SITL.h:71
void zero()
Definition: vector3.h:182
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
AP_Compass_SITL(Compass &)