CalibrateMag sensor class.
More...
#include <mag_cal.h>
|
void | eigSort (Eigen::MatrixXd &w, Eigen::MatrixXd &v) |
|
Eigen::MatrixXd | ellipsoidLS (EigenSTL::vector_Vector3d meas) |
|
Eigen::MatrixXd | ellipsoidRANSAC (EigenSTL::vector_Vector3d meas, int iters, double inlier_thresh) |
|
Eigen::Vector3d | intersect (Eigen::Vector3d r_m, Eigen::Vector3d r_e, Eigen::MatrixXd Q, Eigen::MatrixXd ub, double k) |
|
void | magCal (Eigen::MatrixXd u, Eigen::MatrixXd &A, Eigen::MatrixXd &bb) |
|
bool | set_param (std::string name, double value) |
|
CalibrateMag sensor class.
Definition at line 63 of file mag_cal.h.
rosflight::CalibrateMag::CalibrateMag |
( |
| ) |
|
const double rosflight::CalibrateMag::a11 |
( |
| ) |
const |
|
inline |
The const stuff is to make it read-only.
Definition at line 93 of file mag_cal.h.
const double rosflight::CalibrateMag::a12 |
( |
| ) |
const |
|
inline |
const double rosflight::CalibrateMag::a13 |
( |
| ) |
const |
|
inline |
const double rosflight::CalibrateMag::a21 |
( |
| ) |
const |
|
inline |
const double rosflight::CalibrateMag::a22 |
( |
| ) |
const |
|
inline |
const double rosflight::CalibrateMag::a23 |
( |
| ) |
const |
|
inline |
const double rosflight::CalibrateMag::a31 |
( |
| ) |
const |
|
inline |
const double rosflight::CalibrateMag::a32 |
( |
| ) |
const |
|
inline |
const double rosflight::CalibrateMag::a33 |
( |
| ) |
const |
|
inline |
const double rosflight::CalibrateMag::bx |
( |
| ) |
const |
|
inline |
const double rosflight::CalibrateMag::by |
( |
| ) |
const |
|
inline |
const double rosflight::CalibrateMag::bz |
( |
| ) |
const |
|
inline |
void rosflight::CalibrateMag::do_mag_calibration |
( |
| ) |
|
void rosflight::CalibrateMag::eigSort |
( |
Eigen::MatrixXd & |
w, |
|
|
Eigen::MatrixXd & |
v |
|
) |
| |
|
private |
Eigen::Vector3d rosflight::CalibrateMag::intersect |
( |
Eigen::Vector3d |
r_m, |
|
|
Eigen::Vector3d |
r_e, |
|
|
Eigen::MatrixXd |
Q, |
|
|
Eigen::MatrixXd |
ub, |
|
|
double |
k |
|
) |
| |
|
private |
bool rosflight::CalibrateMag::is_calibrating |
( |
| ) |
|
|
inline |
Check if a calibration is in progress.
- Returns
- True if a calibration is currently in progress
Definition at line 90 of file mag_cal.h.
bool rosflight::CalibrateMag::mag_callback |
( |
const sensor_msgs::MagneticField::ConstPtr & |
mag | ) |
|
set_refence_magnetic_field_strength
- Parameters
-
Definition at line 161 of file mag_cal.cpp.
void rosflight::CalibrateMag::magCal |
( |
Eigen::MatrixXd |
u, |
|
|
Eigen::MatrixXd & |
A, |
|
|
Eigen::MatrixXd & |
bb |
|
) |
| |
|
private |
void rosflight::CalibrateMag::run |
( |
| ) |
|
bool rosflight::CalibrateMag::set_param |
( |
std::string |
name, |
|
|
double |
value |
|
) |
| |
|
private |
void rosflight::CalibrateMag::set_reference_magnetic_field_strength |
( |
double |
reference_magnetic_field | ) |
|
void rosflight::CalibrateMag::start_mag_calibration |
( |
| ) |
|
Begin the magnetometer calibration routine.
Definition at line 139 of file mag_cal.cpp.
Eigen::MatrixXd rosflight::CalibrateMag::A_ |
|
private |
Eigen::MatrixXd rosflight::CalibrateMag::b_ |
|
private |
bool rosflight::CalibrateMag::calibrating_ |
|
private |
whether a temperature calibration is in progress
Definition at line 121 of file mag_cal.h.
double rosflight::CalibrateMag::calibration_time_ |
|
private |
seconds to record data for temperature compensation
Definition at line 123 of file mag_cal.h.
bool rosflight::CalibrateMag::first_time_ |
|
private |
waiting for first measurement for calibration
Definition at line 122 of file mag_cal.h.
double rosflight::CalibrateMag::inlier_thresh_ |
|
private |
threshold to consider measurement an inlier in ellipsoidRANSAC
Definition at line 128 of file mag_cal.h.
Eigen::Vector3d rosflight::CalibrateMag::measurement_prev_ |
|
private |
int rosflight::CalibrateMag::measurement_skip_ |
|
private |
int rosflight::CalibrateMag::measurement_throttle_ |
|
private |
int rosflight::CalibrateMag::ransac_iters_ |
|
private |
number of ransac iterations to fit ellipsoid to mag measurements
Definition at line 125 of file mag_cal.h.
double rosflight::CalibrateMag::reference_field_strength_ |
|
private |
the strength of earth's magnetic field at your location
Definition at line 119 of file mag_cal.h.
double rosflight::CalibrateMag::start_time_ |
|
private |
timestamp of first calibration measurement
Definition at line 124 of file mag_cal.h.
The documentation for this class was generated from the following files: