mag_cal.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * * Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * * Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
38 #include <rosflight/mag_cal.h>
39 #include <cstdio>
40 
41 namespace rosflight
42 {
44  calibrating_(false),
45  nh_private_("~"),
46  reference_field_strength_(1.0),
47  mag_subscriber_(nh_, "/magnetometer", 1)
48 {
49  A_ = Eigen::MatrixXd::Zero(3, 3);
50  b_ = Eigen::MatrixXd::Zero(3, 1);
51  ransac_iters_ = 100;
52  inlier_thresh_ = 200;
53 
54  calibration_time_ = nh_private_.param<double>("calibration_time", 60.0);
55  measurement_skip_ = nh_private_.param<int>("measurement_skip", 20);
56 
57  param_set_client_ = nh_.serviceClient<rosflight_msgs::ParamSet>("param_set");
59 }
60 
62 {
63  // reset calibration parameters
64  bool success = true;
65  // reset soft iron parameters
66  success = success && set_param("MAG_A11_COMP", 1.0f);
67  success = success && set_param("MAG_A12_COMP", 0.0f);
68  success = success && set_param("MAG_A13_COMP", 0.0f);
69  success = success && set_param("MAG_A21_COMP", 0.0f);
70  success = success && set_param("MAG_A22_COMP", 1.0f);
71  success = success && set_param("MAG_A23_COMP", 0.0f);
72  success = success && set_param("MAG_A31_COMP", 0.0f);
73  success = success && set_param("MAG_A32_COMP", 0.0f);
74  success = success && set_param("MAG_A33_COMP", 1.0f);
75 
76  // reset hard iron parameters
77  success = success && set_param("MAG_X_BIAS", 0.0f);
78  success = success && set_param("MAG_Y_BIAS", 0.0f);
79  success = success && set_param("MAG_Z_BIAS", 0.0f);
80 
81  if (!success)
82  {
83  ROS_FATAL("Failed to reset calibration parameters");
84  return;
85  }
86 
88 
89  // wait for data to arrive
90  ros::Duration timeout(3.0);
91  ros::Time start = ros::Time::now();
92  while (ros::Time::now() - start < timeout && first_time_ && ros::ok())
93  {
94  ros::spinOnce();
95  }
96 
97  if (first_time_)
98  {
99  ROS_FATAL("No messages on magnetometer topic, unable to calibrate");
100  return;
101  }
102 
103  while (calibrating_ && ros::ok())
104  {
105  ros::spinOnce();
106  }
107 
108  if (!calibrating_)
109  {
110  // compute calibration
112 
113  // set calibration parameters
114  // set soft iron parameters
115  success = success && set_param("MAG_A11_COMP", a11());
116  success = success && set_param("MAG_A12_COMP", a12());
117  success = success && set_param("MAG_A13_COMP", a13());
118  success = success && set_param("MAG_A21_COMP", a21());
119  success = success && set_param("MAG_A22_COMP", a22());
120  success = success && set_param("MAG_A23_COMP", a23());
121  success = success && set_param("MAG_A31_COMP", a31());
122  success = success && set_param("MAG_A32_COMP", a32());
123  success = success && set_param("MAG_A33_COMP", a33());
124 
125  // set hard iron parameters
126  success = success && set_param("MAG_X_BIAS", bx());
127  success = success && set_param("MAG_Y_BIAS", by());
128  success = success && set_param("MAG_Z_BIAS", bz());
129  }
130 }
131 
132 void CalibrateMag::set_reference_magnetic_field_strength(double reference_magnetic_field)
133 {
134  reference_field_strength_ = reference_magnetic_field;
135 }
136 
138 {
139  calibrating_ = true;
140 
141  first_time_ = true;
142  start_time_ = 0;
143 
144  measurement_prev_ = Eigen::Vector3d::Zero();
145  measurements_.clear();
146 }
147 
149 {
150  // fit ellipsoid to measurements according to Li paper but in RANSAC form
151  ROS_INFO("Collected %u measurements. Fitting ellipsoid.", (uint32_t)measurements_.size());
153 
154  // magnetometer calibration parameters according to Renaudin paper
155  ROS_INFO("Computing calibration parameters.");
156  magCal(u, A_, b_);
157 }
158 
159 bool CalibrateMag::mag_callback(const sensor_msgs::MagneticField::ConstPtr &mag)
160 {
161  if (calibrating_)
162  {
163  if (first_time_)
164  {
165  first_time_ = false;
166  ROS_WARN_ONCE("Calibrating Mag, do the mag dance for %g seconds!", calibration_time_);
168  }
169 
170  double elapsed = ros::Time::now().toSec() - start_time_;
171 
172  printf("\r%.1f seconds remaining", calibration_time_ - elapsed);
173 
174  // if still in calibration mode
175  if (elapsed < calibration_time_)
176  {
178  {
179  Eigen::Vector3d measurement;
180  measurement << mag->magnetic_field.x, mag->magnetic_field.y, mag->magnetic_field.z;
181 
182  if (measurement != measurement_prev_)
183  {
184  measurements_.push_back(measurement);
185  }
186  measurement_prev_ = measurement;
187  }
189  }
190  else
191  {
192  ROS_WARN("\rdone!");
193  calibrating_ = false;
194  }
195  }
196 }
197 
198 Eigen::MatrixXd CalibrateMag::ellipsoidRANSAC(EigenSTL::vector_Vector3d meas, int iters, double inlier_thresh)
199 {
200  // initialize random number generator
201  std::random_device random_dev;
202  std::mt19937 generator(random_dev());
203 
204  // RANSAC to find a good ellipsoid fit
205  int inlier_count_best = 0; // number of inliers for best fit
206  EigenSTL::vector_Vector3d inliers_best; // container for inliers to best fit
207  double dist_sum = 0; // sum distances of all measurements from ellipsoid surface
208  int dist_count = 0; // count number distances of all measurements from ellipsoid surface
209  for (unsigned i = 0; i < iters; i++)
210  {
211  // pick 9 random, unique measurements by shuffling measurements
212  // and grabbing the first 9
213  std::shuffle(meas.begin(), meas.end(), generator);
214  EigenSTL::vector_Vector3d meas_sample;
215  for (unsigned j = 0; j < 9; j++)
216  {
217  meas_sample.push_back(meas[j]);
218  }
219 
220  // fit ellipsoid to 9 random points
221  Eigen::MatrixXd u = ellipsoidLS(meas_sample);
222 
223  // check if LS fit is actually an ellipsoid (paragraph of Li following eq. 2-4)
224  // unpack needed parts of u
225  double a = u(0);
226  double b = u(1);
227  double c = u(2);
228  double f = u(3);
229  double g = u(4);
230  double h = u(5);
231  double p = u(6);
232  double q = u(7);
233  double r = u(8);
234  double d = u(9);
235 
236  double I = a + b + c;
237  double J = a * b + b * c + a * c - f * f - g * g - h * h;
238 
239  if (4 * J - I * I <= 0)
240  {
241  continue;
242  }
243 
244  // eq. 15 of Renaudin and eqs. 1 and 4 of Li
245  Eigen::MatrixXd Q(3, 3);
246  Q << a, h, g, h, b, f, g, f, c;
247 
248  Eigen::MatrixXd ub(3, 1);
249  ub << 2 * p, 2 * q, 2 * r;
250  double k = d;
251 
252  // eq. 21 of Renaudin (should be negative according to eq. 16)
253  // this is the vector to the ellipsoid center
254  Eigen::MatrixXd bb = -0.5 * (Q.inverse() * ub);
255  Eigen::Vector3d r_e;
256  r_e << bb(0), bb(1), bb(2);
257 
258  // count inliers and store inliers
259  int inlier_count = 0;
261  for (unsigned j = 0; j < meas.size(); j++)
262  {
263  // compute the vector from ellipsoid center to surface along
264  // measurement vector and a one from the perturbed measurement
265  Eigen::Vector3d perturb = Eigen::Vector3d::Ones() * 0.1;
266  Eigen::Vector3d r_int = intersect(meas[j], r_e, Q, ub, k);
267  Eigen::Vector3d r_int_prime = intersect(meas[j] + perturb, r_e, Q, ub, k);
268 
269  // now compute the vector normal to the surface
270  Eigen::Vector3d r_align = r_int_prime - r_int;
271  Eigen::Vector3d r_normal = r_align.cross(r_int.cross(r_int_prime));
272  Eigen::Vector3d i_normal = r_normal / r_normal.norm();
273 
274  // get vector from surface to measurement and take dot product
275  // with surface normal vector to find distance from ellipsoid fit
276  Eigen::Vector3d r_sm = meas[j] - r_e - r_int;
277  double dist = r_sm.dot(i_normal);
278  dist_sum += dist;
279  dist_count++;
280 
281  // check measurement distance against inlier threshold
282  if (fabs(dist) < inlier_thresh)
283  {
284  inliers.push_back(meas[j]);
285  inlier_count++;
286  }
287  }
288 
289  // save best inliers and their count
290  if (inlier_count > inlier_count_best)
291  {
292  inliers_best.clear();
293  for (unsigned j = 0; j < inliers.size(); j++)
294  {
295  inliers_best.push_back(inliers[j]);
296  }
297  inlier_count_best = inlier_count;
298  }
299  }
300 
301  // check average measurement distance from surface
302  double dist_avg = dist_sum / dist_count;
303  if (inlier_thresh > fabs(dist_avg))
304  {
305  ROS_WARN("Inlier threshold is greater than average measurement distance from surface. Reduce inlier threshold.");
306  ROS_INFO("Inlier threshold = %7.1f, Average measurement distance = %7.1f", inlier_thresh_, dist_avg);
307  }
308 
309  // perform LS on set of best inliers
310  Eigen::MatrixXd u_final = ellipsoidLS(inliers_best);
311 
312  return u_final;
313 }
314 
315 Eigen::Vector3d CalibrateMag::intersect(Eigen::Vector3d r_m,
316  Eigen::Vector3d r_e,
317  Eigen::MatrixXd Q,
318  Eigen::MatrixXd ub,
319  double k)
320 {
321  // form unit vector from ellipsoid center (r_e) pointing to measurement
322  Eigen::Vector3d r_em = r_m - r_e;
323  Eigen::Vector3d i_em = r_em / r_em.norm();
324 
325  // solve quadratic equation for alpha, which determines how much to scale
326  // i_em to intersect the ellipsoid surface (this is in Jerel's notebook)
327  double A = (i_em.transpose() * Q * i_em)(0);
328  double B = (2 * (i_em.transpose() * Q * r_e + ub.transpose() * i_em))(0);
329  double C = (ub.transpose() * r_e + r_e.transpose() * Q * r_e)(0) + k;
330  double alpha = (-B + sqrt(B * B - 4 * A * C)) / (2 * A);
331 
332  // compute vector from ellipsoid center to its surface along measurement vector
333  Eigen::Vector3d r_int = r_e + alpha * i_em;
334 
335  return r_int;
336 }
337 
338 void CalibrateMag::eigSort(Eigen::MatrixXd &w, Eigen::MatrixXd &v)
339 {
340  // create index array
341  int idx[w.cols()];
342  for (unsigned i = 0; i < w.cols(); i++)
343  {
344  idx[i] = i;
345  }
346 
347  // do a bubble sort and keep track of where values go with the index array
348  int has_changed = 1; // true
349  Eigen::MatrixXd w_sort = w;
350  while (has_changed == 1)
351  {
352  has_changed = 0; // false
353  for (unsigned i = 0; i < w.cols() - 1; i++)
354  {
355  if (w_sort(i) < w_sort(i + 1))
356  {
357  // switch values
358  double tmp = w_sort(i);
359  w_sort(i) = w_sort(i + 1);
360  w_sort(i + 1) = tmp;
361 
362  // switch indices
363  tmp = idx[i];
364  idx[i] = idx[i + 1];
365  idx[i + 1] = tmp;
366 
367  has_changed = 1; // true
368  }
369  }
370  }
371 
372  // add sorted eigenvalues/eigenvectors to output
373  Eigen::MatrixXd w1 = w;
374  Eigen::MatrixXd v1 = v;
375  for (unsigned i = 0; i < w.cols(); i++)
376  {
377  w1(i) = w(idx[i]);
378  v1.col(i) = v.col(idx[i]);
379  }
380  w = w1;
381  v = v1;
382 }
383 
384 /*
385  This function gets ellipsoid parameters via least squares on ellipsoidal data
386  according to the paper: Li, Qingde, and John G. Griffiths. "Least squares ellipsoid
387  specific fitting." Geometric modeling and processing, 2004. proceedings. IEEE, 2004.
388  */
390 {
391  // form D matrix from eq. 6
392  Eigen::MatrixXd D(10, meas.size());
393  for (unsigned i = 0; i < D.cols(); i++)
394  {
395  // unpack measurement components
396  double x = meas[i](0);
397  double y = meas[i](1);
398  double z = meas[i](2);
399 
400  // fill in the D matrix
401  D(0, i) = x * x;
402  D(1, i) = y * y;
403  D(2, i) = z * z;
404  D(3, i) = 2 * y * z;
405  D(4, i) = 2 * x * z;
406  D(5, i) = 2 * x * y;
407  D(6, i) = 2 * x;
408  D(7, i) = 2 * y;
409  D(8, i) = 2 * z;
410  D(9, i) = 1;
411  }
412 
413  // form the C1 matrix from eq. 7
414  double k = 4;
415  Eigen::MatrixXd C1 = Eigen::MatrixXd::Zero(6, 6);
416  C1(0, 0) = -1;
417  C1(0, 1) = k / 2 - 1;
418  C1(0, 2) = k / 2 - 1;
419  C1(1, 0) = k / 2 - 1;
420  C1(1, 1) = -1;
421  C1(1, 2) = k / 2 - 1;
422  C1(2, 0) = k / 2 - 1;
423  C1(2, 1) = k / 2 - 1;
424  C1(2, 2) = -1;
425  C1(3, 3) = -k;
426  C1(4, 4) = -k;
427  C1(5, 5) = -k;
428 
429  // decompose D*D^T according to eq. 11
430  Eigen::MatrixXd DDt = D * D.transpose();
431  Eigen::MatrixXd S11 = DDt.block(0, 0, 6, 6);
432  Eigen::MatrixXd S12 = DDt.block(0, 6, 6, 4);
433  Eigen::MatrixXd S22 = DDt.block(6, 6, 4, 4);
434 
435  // solve eigensystem in eq. 15
436  Eigen::MatrixXd ES = C1.inverse() * (S11 - S12 * S22.inverse() * S12.transpose());
437  Eigen::EigenSolver<Eigen::MatrixXd> eigensolver(ES);
438  if (eigensolver.info() != Eigen::Success)
439  {
440  abort();
441  }
442  Eigen::MatrixXd w = eigensolver.eigenvalues().real().transpose();
443  Eigen::MatrixXd V = eigensolver.eigenvectors().real();
444 
445  // sort eigenvalues and eigenvectors from most positive to most negative
446  eigSort(w, V);
447 
448  // compute solution vector defined in paragraph below eq. 15
449  Eigen::MatrixXd u1 = V.col(0);
450  Eigen::MatrixXd u2 = -(S22.inverse() * S12.transpose() * u1);
451  Eigen::MatrixXd u(10, 1);
452  u.block(0, 0, 6, 1) = u1;
453  u.block(6, 0, 4, 1) = u2;
454 
455  return u;
456 }
457 
458 /*
459  This function compute magnetometer calibration parameters according to Section 5.3 of the
460 paper: Renaudin, Valérie, Muhammad Haris Afzal, and Gérard Lachapelle. "Complete triaxis
461 magnetometer calibration in the magnetic domain." Journal of sensors 2010 (2010).
462 */
463 void CalibrateMag::magCal(Eigen::MatrixXd u, Eigen::MatrixXd &A, Eigen::MatrixXd &bb)
464 {
465  // unpack coefficients
466  double a = u(0);
467  double b = u(1);
468  double c = u(2);
469  double f = u(3);
470  double g = u(4);
471  double h = u(5);
472  double p = u(6);
473  double q = u(7);
474  double r = u(8);
475  double d = u(9);
476 
477  // compute Q, u, and k according to eq. 15 of Renaudin and eqs. 1 and 4 of Li
478  Eigen::MatrixXd Q(3, 3);
479  Q << a, h, g, h, b, f, g, f, c;
480 
481  Eigen::MatrixXd ub(3, 1);
482  ub << 2 * p, 2 * q, 2 * r;
483  double k = d;
484 
485  // extract bb according to eq. 21 of Renaudin (should be negative according to eq. 16)
486  bb = -0.5 * (Q.inverse() * ub);
487 
488  // eigendecomposition of Q according to eq. 22 of Renaudin
489  Eigen::EigenSolver<Eigen::MatrixXd> eigensolver(Q);
490  if (eigensolver.info() != Eigen::Success)
491  {
492  abort();
493  }
494  Eigen::MatrixXd D = eigensolver.eigenvalues().real().asDiagonal();
495  Eigen::MatrixXd V = eigensolver.eigenvectors().real();
496 
497  // compute alpha according to eq. 27 of Renaudin (the denominator needs to be multiplied by -1)
498  double Hm = reference_field_strength_; // (uT) Provo, UT magnetic field magnitude
499  Eigen::MatrixXd utVDiVtu = ub.transpose() * V * D.inverse() * V.transpose() * ub;
500  double alpha = (4. * Hm * Hm) / (utVDiVtu(0) - 4 * k);
501 
502  // now compute A from eq. 8 and 28 of Renaudin
503  A = V * (alpha * D).cwiseSqrt() * V.transpose();
504 }
505 
506 bool CalibrateMag::set_param(std::string name, double value)
507 {
508  rosflight_msgs::ParamSet srv;
509  srv.request.name = name;
510  srv.request.value = value;
511 
512  if (param_set_client_.call(srv))
513  {
514  return srv.response.exists;
515  }
516  else
517  {
518  return false;
519  }
520 }
521 
522 } // namespace rosflight
d
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::NodeHandle nh_
Definition: mag_cal.h:107
const double a23() const
Definition: mag_cal.h:96
#define ROS_FATAL(...)
Eigen::Vector3d intersect(Eigen::Vector3d r_m, Eigen::Vector3d r_e, Eigen::MatrixXd Q, Eigen::MatrixXd ub, double k)
Definition: mag_cal.cpp:315
message_filters::Subscriber< sensor_msgs::MagneticField > mag_subscriber_
Definition: mag_cal.h:110
Eigen::MatrixXd b_
Definition: mag_cal.h:115
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
const double a21() const
Definition: mag_cal.h:94
f
double calibration_time_
seconds to record data for temperature compensation
Definition: mag_cal.h:121
bool calibrating_
whether a temperature calibration is in progress
Definition: mag_cal.h:119
void set_reference_magnetic_field_strength(double reference_magnetic_field)
Definition: mag_cal.cpp:132
bool call(MReq &req, MRes &res)
ros::NodeHandle nh_private_
Definition: mag_cal.h:108
bool first_time_
waiting for first measurement for calibration
Definition: mag_cal.h:120
const double bz() const
Definition: mag_cal.h:102
int ransac_iters_
number of ransac iterations to fit ellipsoid to mag measurements
Definition: mag_cal.h:123
Eigen::MatrixXd A_
Definition: mag_cal.h:115
const double a31() const
Definition: mag_cal.h:97
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
Eigen::MatrixXd ellipsoidRANSAC(EigenSTL::vector_Vector3d meas, int iters, double inlier_thresh)
Definition: mag_cal.cpp:198
const double a32() const
Definition: mag_cal.h:98
bool set_param(std::string name, double value)
Definition: mag_cal.cpp:506
#define ROS_WARN_ONCE(...)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const double a13() const
Definition: mag_cal.h:93
const double by() const
Definition: mag_cal.h:101
ROSCPP_DECL bool ok()
ros::ServiceClient param_set_client_
Definition: mag_cal.h:113
TFSIMD_FORCE_INLINE const tfScalar & x() const
Eigen::Vector3d measurement_prev_
Definition: mag_cal.h:127
const double a33() const
Definition: mag_cal.h:99
const double a11() const
The const stuff is to make it read-only.
Definition: mag_cal.h:91
TFSIMD_FORCE_INLINE const tfScalar & z() const
double inlier_thresh_
threshold to consider measurement an inlier in ellipsoidRANSAC
Definition: mag_cal.h:126
double start_time_
timestamp of first calibration measurement
Definition: mag_cal.h:122
TFSIMD_FORCE_INLINE const tfScalar & w() const
void magCal(Eigen::MatrixXd u, Eigen::MatrixXd &A, Eigen::MatrixXd &bb)
Definition: mag_cal.cpp:463
Eigen::MatrixXd ellipsoidLS(EigenSTL::vector_Vector3d meas)
Definition: mag_cal.cpp:389
void start_mag_calibration()
Begin the magnetometer calibration routine.
Definition: mag_cal.cpp:137
static Time now()
bool mag_callback(const sensor_msgs::MagneticField::ConstPtr &mag)
set_refence_magnetic_field_strength
Definition: mag_cal.cpp:159
EigenSTL::vector_Vector3d measurements_
Definition: mag_cal.h:128
const double a12() const
Definition: mag_cal.h:92
ROSCPP_DECL void spinOnce()
double reference_field_strength_
the strength of earth&#39;s magnetic field at your location
Definition: mag_cal.h:117
void eigSort(Eigen::MatrixXd &w, Eigen::MatrixXd &v)
Definition: mag_cal.cpp:338
const double bx() const
Definition: mag_cal.h:100
const double a22() const
Definition: mag_cal.h:95
Connection registerCallback(const C &callback)


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:09:25