46 reference_field_strength_(1.0),
47 mag_subscriber_(nh_,
"/magnetometer", 1)
49 A_ = Eigen::MatrixXd::Zero(3, 3);
50 b_ = Eigen::MatrixXd::Zero(3, 1);
66 success = success &&
set_param(
"MAG_A11_COMP", 1.0
f);
67 success = success &&
set_param(
"MAG_A12_COMP", 0.0
f);
68 success = success &&
set_param(
"MAG_A13_COMP", 0.0
f);
69 success = success &&
set_param(
"MAG_A21_COMP", 0.0
f);
70 success = success &&
set_param(
"MAG_A22_COMP", 1.0
f);
71 success = success &&
set_param(
"MAG_A23_COMP", 0.0
f);
72 success = success &&
set_param(
"MAG_A31_COMP", 0.0
f);
73 success = success &&
set_param(
"MAG_A32_COMP", 0.0
f);
74 success = success &&
set_param(
"MAG_A33_COMP", 1.0
f);
77 success = success &&
set_param(
"MAG_X_BIAS", 0.0
f);
78 success = success &&
set_param(
"MAG_Y_BIAS", 0.0
f);
79 success = success &&
set_param(
"MAG_Z_BIAS", 0.0
f);
83 ROS_FATAL(
"Failed to reset calibration parameters");
99 ROS_FATAL(
"No messages on magnetometer topic, unable to calibrate");
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());
155 ROS_INFO(
"Computing calibration parameters.");
179 Eigen::Vector3d measurement;
180 measurement << mag->magnetic_field.x, mag->magnetic_field.y, mag->magnetic_field.z;
201 std::random_device random_dev;
202 std::mt19937 generator(random_dev());
205 int inlier_count_best = 0;
209 for (
unsigned i = 0; i < iters; i++)
213 std::shuffle(meas.begin(), meas.end(), generator);
215 for (
unsigned j = 0; j < 9; j++)
217 meas_sample.push_back(meas[j]);
236 double I = a + b + c;
237 double J = a * b + b * c + a * c - f * f - g * g - h * h;
239 if (4 * J - I * I <= 0)
245 Eigen::MatrixXd Q(3, 3);
246 Q << a, h, g, h, b, f, g, f, c;
248 Eigen::MatrixXd ub(3, 1);
249 ub << 2 * p, 2 * q, 2 * r;
254 Eigen::MatrixXd bb = -0.5 * (Q.inverse() * ub);
256 r_e << bb(0), bb(1), bb(2);
259 int inlier_count = 0;
261 for (
unsigned j = 0; j < meas.size(); j++)
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);
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();
276 Eigen::Vector3d r_sm = meas[j] - r_e - r_int;
277 double dist = r_sm.dot(i_normal);
282 if (fabs(dist) < inlier_thresh)
284 inliers.push_back(meas[j]);
290 if (inlier_count > inlier_count_best)
292 inliers_best.clear();
293 for (
unsigned j = 0; j < inliers.size(); j++)
295 inliers_best.push_back(inliers[j]);
297 inlier_count_best = inlier_count;
302 double dist_avg = dist_sum / dist_count;
303 if (inlier_thresh > fabs(dist_avg))
305 ROS_WARN(
"Inlier threshold is greater than average measurement distance from surface. Reduce inlier threshold.");
310 Eigen::MatrixXd u_final =
ellipsoidLS(inliers_best);
322 Eigen::Vector3d r_em = r_m - r_e;
323 Eigen::Vector3d i_em = r_em / r_em.norm();
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);
333 Eigen::Vector3d r_int = r_e + alpha * i_em;
342 for (
unsigned i = 0; i < w.cols(); i++)
349 Eigen::MatrixXd w_sort = w;
350 while (has_changed == 1)
353 for (
unsigned i = 0; i < w.cols() - 1; i++)
355 if (w_sort(i) < w_sort(i + 1))
358 double tmp = w_sort(i);
359 w_sort(i) = w_sort(i + 1);
373 Eigen::MatrixXd w1 = w;
374 Eigen::MatrixXd v1 = v;
375 for (
unsigned i = 0; i < w.cols(); i++)
378 v1.col(i) = v.col(idx[i]);
392 Eigen::MatrixXd D(10, meas.size());
393 for (
unsigned i = 0; i < D.cols(); i++)
396 double x = meas[i](0);
397 double y = meas[i](1);
398 double z = meas[i](2);
415 Eigen::MatrixXd C1 = Eigen::MatrixXd::Zero(6, 6);
417 C1(0, 1) = k / 2 - 1;
418 C1(0, 2) = k / 2 - 1;
419 C1(1, 0) = k / 2 - 1;
421 C1(1, 2) = k / 2 - 1;
422 C1(2, 0) = k / 2 - 1;
423 C1(2, 1) = k / 2 - 1;
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);
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)
442 Eigen::MatrixXd
w = eigensolver.eigenvalues().real().transpose();
443 Eigen::MatrixXd V = eigensolver.eigenvectors().real();
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;
478 Eigen::MatrixXd Q(3, 3);
479 Q << a, h, g, h, b, f, g, f, c;
481 Eigen::MatrixXd ub(3, 1);
482 ub << 2 * p, 2 * q, 2 * r;
486 bb = -0.5 * (Q.inverse() * ub);
489 Eigen::EigenSolver<Eigen::MatrixXd> eigensolver(Q);
490 if (eigensolver.info() != Eigen::Success)
494 Eigen::MatrixXd D = eigensolver.eigenvalues().real().asDiagonal();
495 Eigen::MatrixXd V = eigensolver.eigenvectors().real();
499 Eigen::MatrixXd utVDiVtu = ub.transpose() * V * D.inverse() * V.transpose() * ub;
500 double alpha = (4. * Hm * Hm) / (utVDiVtu(0) - 4 * k);
503 A = V * (alpha * D).cwiseSqrt() * V.transpose();
508 rosflight_msgs::ParamSet srv;
509 srv.request.name = name;
510 srv.request.value = value;
514 return srv.response.exists;
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
Eigen::Vector3d intersect(Eigen::Vector3d r_m, Eigen::Vector3d r_e, Eigen::MatrixXd Q, Eigen::MatrixXd ub, double k)
message_filters::Subscriber< sensor_msgs::MagneticField > mag_subscriber_
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
double calibration_time_
seconds to record data for temperature compensation
bool calibrating_
whether a temperature calibration is in progress
void set_reference_magnetic_field_strength(double reference_magnetic_field)
bool call(MReq &req, MRes &res)
ros::NodeHandle nh_private_
bool first_time_
waiting for first measurement for calibration
int ransac_iters_
number of ransac iterations to fit ellipsoid to mag measurements
TFSIMD_FORCE_INLINE const tfScalar & y() const
Eigen::MatrixXd ellipsoidRANSAC(EigenSTL::vector_Vector3d meas, int iters, double inlier_thresh)
bool set_param(std::string name, double value)
#define ROS_WARN_ONCE(...)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::ServiceClient param_set_client_
TFSIMD_FORCE_INLINE const tfScalar & x() const
Eigen::Vector3d measurement_prev_
const double a11() const
The const stuff is to make it read-only.
TFSIMD_FORCE_INLINE const tfScalar & z() const
double inlier_thresh_
threshold to consider measurement an inlier in ellipsoidRANSAC
double start_time_
timestamp of first calibration measurement
TFSIMD_FORCE_INLINE const tfScalar & w() const
void magCal(Eigen::MatrixXd u, Eigen::MatrixXd &A, Eigen::MatrixXd &bb)
void do_mag_calibration()
Eigen::MatrixXd ellipsoidLS(EigenSTL::vector_Vector3d meas)
void start_mag_calibration()
Begin the magnetometer calibration routine.
bool mag_callback(const sensor_msgs::MagneticField::ConstPtr &mag)
set_refence_magnetic_field_strength
EigenSTL::vector_Vector3d measurements_
ROSCPP_DECL void spinOnce()
int measurement_throttle_
double reference_field_strength_
the strength of earth's magnetic field at your location
void eigSort(Eigen::MatrixXd &w, Eigen::MatrixXd &v)
Connection registerCallback(const C &callback)