APM:Libraries
AP_Compass_Backend.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #include "AP_Compass.h"
4 #include "AP_Compass_Backend.h"
5 #include <stdio.h>
6 
7 extern const AP_HAL::HAL& hal;
8 
10  _compass(compass)
11 {
12  _sem = hal.util->new_semaphore();
13 }
14 
15 void AP_Compass_Backend::rotate_field(Vector3f &mag, uint8_t instance)
16 {
18  mag.rotate(MAG_BOARD_ORIENTATION);
19  mag.rotate(state.rotation);
20 
21  if (!state.external) {
22  // and add in AHRS_ORIENTATION setting if not an external compass
24  mag = *_compass._custom_rotation * mag;
25  } else {
27  }
28  } else {
29  // add user selectable orientation
30  mag.rotate((enum Rotation)state.orientation.get());
31  }
32 }
33 
34 void AP_Compass_Backend::publish_raw_field(const Vector3f &mag, uint8_t instance)
35 {
37 
38  // note that we do not set last_update_usec here as otherwise the
39  // EKF and DCM would end up consuming compass data at the full
40  // sensor rate. We want them to consume only the filtered fields
42 
43  _compass._calibrator[instance].new_sample(mag);
44 }
45 
47 {
49 
50  if (state.diagonals.get().is_zero()) {
51  state.diagonals.set(Vector3f(1.0f,1.0f,1.0f));
52  }
53 
54  const Vector3f &offsets = state.offset.get();
55  const Vector3f &diagonals = state.diagonals.get();
56  const Vector3f &offdiagonals = state.offdiagonals.get();
57  const Vector3f &mot = state.motor_compensation.get();
58 
59  // add in the basic offsets
60  mag += offsets;
61 
62  // apply eliptical correction
63  Matrix3f mat(
64  diagonals.x, offdiagonals.x, offdiagonals.y,
65  offdiagonals.x, diagonals.y, offdiagonals.z,
66  offdiagonals.y, offdiagonals.z, diagonals.z
67  );
68 
69  mag = mat * mag;
70 
71  /*
72  calculate motor-power based compensation
73  note that _motor_offset[] is kept even if compensation is not
74  being applied so it can be logged correctly
75  */
76  state.motor_offset.zero();
77  if (_compass._per_motor.enabled() && i == 0) {
78  // per-motor correction is only valid for first compass
81  state.motor_offset = mot * _compass._thr;
84  if (battery.has_current()) {
85  state.motor_offset = mot * battery.current_amps();
86  }
87  }
88 
89  /*
90  we apply the motor offsets after we apply the eliptical
91  correction. This is needed to match the way that the motor
92  compensation values are calculated, as they are calculated based
93  on final field outputs, not on the raw outputs
94  */
95  mag += state.motor_offset;
96 }
97 
98 /*
99  copy latest data to the frontend from a backend
100  */
101 void AP_Compass_Backend::publish_filtered_field(const Vector3f &mag, uint8_t instance)
102 {
104 
105  state.field = mag;
106 
107  state.last_update_ms = AP_HAL::millis();
109 }
110 
111 void AP_Compass_Backend::set_last_update_usec(uint32_t last_update, uint8_t instance)
112 {
114  state.last_update_usec = last_update;
115 }
116 
117 /*
118  register a new backend with frontend, returning instance which
119  should be used in publish_field()
120  */
122 {
123  return _compass.register_compass();
124 }
125 
126 
127 /*
128  set dev_id for an instance
129 */
130 void AP_Compass_Backend::set_dev_id(uint8_t instance, uint32_t dev_id)
131 {
132  _compass._state[instance].dev_id.set_and_notify(dev_id);
133 }
134 
135 /*
136  set external for an instance
137 */
138 void AP_Compass_Backend::set_external(uint8_t instance, bool external)
139 {
140  if (_compass._state[instance].external != 2) {
141  _compass._state[instance].external.set_and_notify(external);
142  }
143 }
144 
145 bool AP_Compass_Backend::is_external(uint8_t instance)
146 {
147  return _compass._state[instance].external;
148 }
149 
150 // set rotation of an instance
151 void AP_Compass_Backend::set_rotation(uint8_t instance, enum Rotation rotation)
152 {
153  _compass._state[instance].rotation = rotation;
154 }
155 
156 static constexpr float FILTER_KOEF = 0.1f;
157 
158 /* Check that the compass value is valid by using a mean filter. If
159  * the value is further than filtrer_range from mean value, it is
160  * rejected.
161 */
163 {
164 
165 
166  if (field.is_inf() || field.is_nan()) {
167  return false;
168  }
169 
170  const float range = (float)_compass.get_filter_range();
171  if (range <= 0) {
172  return true;
173  }
174 
175  const float length = field.length();
176 
178  _mean_field_length = length;
179  return true;
180  }
181 
182  bool ret = true;
183  const float d = fabsf(_mean_field_length - length) / (_mean_field_length + length); // diff divide by mean value in percent ( with the *200.0f on later line)
184  float koeff = FILTER_KOEF;
185 
186  if (d * 200.0f > range) { // check the difference from mean value outside allowed range
187  // printf("\nCompass field length error: mean %f got %f\n", (double)_mean_field_length, (double)length );
188  ret = false;
189  koeff /= (d * 10.0f); // 2.5 and more, so one bad sample never change mean more than 4%
190  _error_count++;
191  }
192  _mean_field_length = _mean_field_length * (1 - koeff) + length * koeff; // complimentary filter 1/k
193 
194  return ret;
195 }
196 
uint8_t register_compass(void)
Definition: AP_Compass.cpp:503
void new_sample(const Vector3f &sample)
Vector3< float > Vector3f
Definition: vector3.h:246
void set_last_update_usec(uint32_t last_update, uint8_t instance)
void set_external(uint8_t instance, bool external)
uint32_t last_update_usec
Definition: AP_Compass.h:452
bool is_inf(void) const
Definition: vector3.cpp:321
float _thr
Definition: AP_Compass.h:421
void rotate_field(Vector3f &mag, uint8_t instance)
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
bool is_nan(void) const
Definition: vector3.cpp:315
void correct_field(Vector3f &mag, uint8_t i)
bool field_ok(const Vector3f &field)
enum Rotation rotation
Definition: AP_Compass.h:455
AP_HAL::Util * util
Definition: HAL.h:115
#define AP_COMPASS_MOT_COMP_THROTTLE
Definition: AP_Compass.h:19
virtual Semaphore * new_semaphore(void)
Definition: Util.h:108
void set_dev_id(uint8_t instance, uint32_t dev_id)
AP_Vector3f diagonals
Definition: AP_Compass.h:428
Rotation
Definition: rotations.h:27
AP_Vector3f offdiagonals
Definition: AP_Compass.h:429
CompassCalibrator _calibrator[COMPASS_MAX_INSTANCES]
Definition: AP_Compass.h:460
bool enabled(void) const
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
uint8_t get_filter_range() const
Definition: AP_Compass.h:331
#define constexpr
Definition: AP_HAL_Macros.h:16
uint8_t register_compass(void) const
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
static constexpr float FILTER_KOEF
bool has_current(uint8_t instance) const
has_current - returns true if battery monitor instance provides current info
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
AP_Vector3f offset
Definition: AP_Compass.h:427
T z
Definition: vector3.h:67
static int state
Definition: Util.cpp:20
float current_amps(uint8_t instance) const
current_amps - returns the instantaneous current draw in amperes
AP_Int8 _motor_comp_type
Definition: AP_Compass.h:418
static Compass compass
Definition: AHRS_Test.cpp:20
AP_HAL::Semaphore * _sem
AP_BattMonitor & battery()
float length(void) const
Definition: vector3.cpp:288
void rotate(enum Rotation rotation)
Definition: vector3.cpp:28
Compass_PerMotor _per_motor
Definition: AP_Compass.h:463
Vector3f motor_offset
Definition: AP_Compass.h:445
Matrix3f * _custom_rotation
Definition: AP_Compass.h:399
void set_rotation(uint8_t instance, enum Rotation rotation)
uint32_t last_update_ms
Definition: AP_Compass.h:451
bool is_external(uint8_t instance)
void publish_raw_field(const Vector3f &mag, uint8_t instance)
#define AP_COMPASS_MOT_COMP_CURRENT
Definition: AP_Compass.h:20
void compensate(Vector3f &offset)
uint32_t micros()
Definition: system.cpp:152
struct Compass::mag_state _state[COMPASS_MAX_INSTANCES]
void zero()
Definition: vector3.h:182
T x
Definition: vector3.h:67
enum Rotation _board_orientation
Definition: AP_Compass.h:398
AP_Vector3f motor_compensation
Definition: AP_Compass.h:442
AP_Compass_Backend(Compass &compass)