APM:Libraries
Compass_learn.cpp
Go to the documentation of this file.
1 #include <AP_Math/AP_Math.h>
2 #include <AP_AHRS/AP_AHRS.h>
3 
6 #include <DataFlash/DataFlash.h>
7 
8 #include "Compass_learn.h"
9 
10 #include <stdio.h>
11 
12 extern const AP_HAL::HAL &hal;
13 
14 // constructor
16  ahrs(_ahrs),
17  compass(_compass)
18 {
19 }
20 
21 /*
22  update when new compass sample available
23  */
25 {
27  !hal.util->get_soft_armed() || ahrs.get_time_flying_ms() < 3000) {
28  // only learn when flying and with enough time to be clear of
29  // the ground
30  return;
31  }
32 
33  if (!have_earth_field) {
34  Location loc;
35  if (!ahrs.get_position(loc)) {
36  // need to wait till we have a global position
37  return;
38  }
39 
40  // setup the expected earth field at this location
41  float declination_deg=0, inclination_deg=0, intensity_gauss=0;
42  AP_Declination::get_mag_field_ef(loc.lat*1.0e-7, loc.lng*1.0e-7, intensity_gauss, declination_deg, inclination_deg);
43 
44  // create earth field
45  mag_ef = Vector3f(intensity_gauss*1000, 0.0, 0.0);
46  Matrix3f R;
47 
48  R.from_euler(0.0f, -ToRad(inclination_deg), ToRad(declination_deg));
49  mag_ef = R * mag_ef;
50 
51  sem = hal.util->new_semaphore();
52 
53  have_earth_field = true;
54 
55  // form eliptical correction matrix and invert it. This is
56  // needed to remove the effects of the eliptical correction
57  // when calculating new offsets
58  const Vector3f &diagonals = compass.get_diagonals(0);
59  const Vector3f &offdiagonals = compass.get_offdiagonals(0);
60  mat = Matrix3f(
61  diagonals.x, offdiagonals.x, offdiagonals.y,
62  offdiagonals.x, diagonals.y, offdiagonals.z,
63  offdiagonals.y, offdiagonals.z, diagonals.z
64  );
65  if (!mat.invert()) {
66  // if we can't invert, use the identity matrix
67  mat.identity();
68  }
69 
70  // set initial error to field intensity
71  for (uint16_t i=0; i<num_sectors; i++) {
72  errors[i] = intensity_gauss*1000;
73  }
74 
76  }
77 
78  if (sample_available) {
79  // last sample still being processed by IO thread
80  return;
81  }
82 
83  Vector3f field = compass.get_field(0);
84  Vector3f field_change = field - last_field;
85  if (field_change.length() < min_field_change) {
86  return;
87  }
88 
89  if (sem->take_nonblocking()) {
90  // give a sample to the backend to process
91  new_sample.field = field;
94  sample_available = true;
95  last_field = field;
96  num_samples++;
97  sem->give();
98  }
99 
100  if (sample_available) {
101  DataFlash_Class::instance()->Log_Write("COFS", "TimeUS,OfsX,OfsY,OfsZ,Var,Yaw,WVar,N", "QffffffI",
103  (double)best_offsets.x,
104  (double)best_offsets.y,
105  (double)best_offsets.z,
106  (double)best_error,
107  (double)best_yaw_deg,
108  (double)worst_error,
109  num_samples);
110  }
111 
112  if (!converged && sem->take_nonblocking()) {
113  // stop updating the offsets once converged
115  if (num_samples > 30 && best_error < 50 && worst_error > 65) {
116  // set the offsets and enable compass for EKF use. Let the
117  // EKF learn the remaining compass offset error
119  compass.set_use_for_yaw(0, true);
121  converged = true;
122  }
123  sem->give();
124  }
125 }
126 
127 /*
128  we run the math intensive calculations in the IO thread
129  */
131 {
132  if (!sample_available) {
133  return;
134  }
135  struct sample s;
136  if (!sem->take_nonblocking()) {
137  return;
138  }
139  s = new_sample;
140  sample_available = false;
141  sem->give();
142 
143  process_sample(s);
144 }
145 
146 /*
147  process a new compass sample
148  */
150 {
151  uint16_t besti = 0;
152  float bestv = 0, worstv=0;
153 
154  /*
155  we run through the 72 possible yaw error values, and for each
156  one we calculate a value for the compass offsets if that yaw
157  error is correct.
158  */
159  for (uint16_t i=0; i<num_sectors; i++) {
160  float yaw_err_deg = i*(360/num_sectors);
161 
162  // form rotation matrix for the euler attitude
163  Matrix3f dcm;
164  dcm.from_euler(s.attitude.x, s.attitude.y, wrap_2PI(s.attitude.z + radians(yaw_err_deg)));
165 
166  // calculate the field we would expect to get if this yaw error is correct
167  Vector3f expected_field = dcm.transposed() * mag_ef;
168 
169  // calculate a value for the compass offsets for this yaw error
170  Vector3f v1 = mat * s.field;
171  Vector3f v2 = mat * expected_field;
172  Vector3f offsets = (v2 - v1) + s.offsets;
173  float delta = (offsets - predicted_offsets[i]).length();
174 
175  if (num_samples == 1) {
176  predicted_offsets[i] = offsets;
177  } else {
178  // lowpass the predicted offsets and the error
179  const float learn_rate = 0.92;
180  predicted_offsets[i] = predicted_offsets[i] * learn_rate + offsets * (1-learn_rate);
181  errors[i] = errors[i] * learn_rate + delta * (1-learn_rate);
182  }
183 
184  // keep track of the current best prediction
185  if (i == 0 || errors[i] < bestv) {
186  besti = i;
187  bestv = errors[i];
188  }
189  // also keep the worst error. This is used as part of the convergence test
190  if (i == 0 || errors[i] > worstv) {
191  worstv = errors[i];
192  }
193  }
194 
195  if (sem->take_nonblocking()) {
196  // pass the current estimate to the front-end
198  best_error = bestv;
199  worst_error = worstv;
200  best_yaw_deg = wrap_360(degrees(s.attitude.z) + besti * (360/num_sectors));
201  sem->give();
202  }
203 }
bool get_soft_armed() const
Definition: Util.h:15
float worst_error
Definition: Compass_learn.h:54
float roll
Definition: AP_AHRS.h:224
Vector3< float > Vector3f
Definition: vector3.h:246
void set_learn_type(enum LearnType type, bool save)
Definition: AP_Compass.h:318
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
CompassLearn(AP_AHRS &ahrs, Compass &compass)
Vector3f mag_ef
Definition: Compass_learn.h:30
virtual bool get_position(struct Location &loc) const =0
#define ToRad(x)
Definition: AP_Common.h:53
float best_error
Definition: Compass_learn.h:52
float pitch
Definition: AP_AHRS.h:225
AP_HAL::Util * util
Definition: HAL.h:115
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
float yaw
Definition: AP_AHRS.h:226
virtual Semaphore * new_semaphore(void)
Definition: Util.h:108
Matrix3< float > Matrix3f
Definition: matrix3.h:270
void set_offsets(uint8_t i, const Vector3f &offsets)
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
bool have_earth_field
Definition: Compass_learn.h:20
static int8_t delta
Definition: RCOutput.cpp:21
void io_timer(void)
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
Definition: AP_Compass.h:122
Matrix3f mat
Definition: Compass_learn.h:44
const Vector3f & get_diagonals(uint8_t i) const
Definition: AP_Compass.h:169
virtual bool take_nonblocking() WARN_IF_UNUSED=0
float wrap_360(const T angle, float unit_mod)
Definition: AP_Math.cpp:123
Compass & compass
Definition: Compass_learn.h:19
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
#define f(i)
void set_use_for_yaw(uint8_t i, bool use)
Definition: AP_Compass.h:200
T y
Definition: vector3.h:67
const Vector3f & get_offsets(uint8_t i) const
Definition: AP_Compass.h:166
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
uint64_t micros64()
Definition: system.cpp:162
static const uint16_t num_sectors
Definition: Compass_learn.h:23
virtual bool give()=0
Vector3f last_field
Definition: Compass_learn.h:48
static Compass compass
Definition: AHRS_Test.cpp:20
AP_HAL::Semaphore * sem
Definition: Compass_learn.h:33
void update(void)
float length(void) const
Definition: vector3.cpp:288
enum LearnType get_learn_type(void) const
Definition: AP_Compass.h:313
bool sample_available
Definition: Compass_learn.h:47
bool invert()
Definition: matrix3.cpp:227
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
float wrap_2PI(const T radian)
Definition: AP_Math.cpp:167
static bool get_mag_field_ef(float latitude_deg, float longitude_deg, float &intensity_gauss, float &declination_deg, float &inclination_deg)
virtual void register_io_process(AP_HAL::MemberProc)=0
static constexpr float radians(float deg)
Definition: AP_Math.h:158
static const uint32_t min_field_change
Definition: Compass_learn.h:49
uint32_t get_time_flying_ms(void) const
Definition: AP_AHRS.h:126
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
#define degrees(x)
Definition: moduletest.c:23
struct sample new_sample
Definition: Compass_learn.h:46
float errors[num_sectors]
Definition: Compass_learn.h:26
void save_offsets(uint8_t i)
float best_yaw_deg
Definition: Compass_learn.h:53
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
Vector3f predicted_offsets[num_sectors]
Definition: Compass_learn.h:25
uint32_t num_samples
Definition: Compass_learn.h:27
void process_sample(const struct sample &s)
const AP_AHRS & ahrs
Definition: Compass_learn.h:18
void identity(void)
Definition: matrix3.h:219
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
Vector3f best_offsets
Definition: Compass_learn.h:51
T x
Definition: vector3.h:67
const Vector3f & get_offdiagonals(uint8_t i) const
Definition: AP_Compass.h:172