Public Member Functions | Private Member Functions | Private Attributes | List of all members
rosflight::CalibrateMag Class Reference

CalibrateMag sensor class. More...

#include <mag_cal.h>

Public Member Functions

const double a11 () const
 The const stuff is to make it read-only. More...
 
const double a12 () const
 
const double a13 () const
 
const double a21 () const
 
const double a22 () const
 
const double a23 () const
 
const double a31 () const
 
const double a32 () const
 
const double a33 () const
 
const double bx () const
 
const double by () const
 
const double bz () const
 
 CalibrateMag ()
 
void do_mag_calibration ()
 
bool is_calibrating ()
 Check if a calibration is in progress. More...
 
bool mag_callback (const sensor_msgs::MagneticField::ConstPtr &mag)
 set_refence_magnetic_field_strength More...
 
void run ()
 
void set_reference_magnetic_field_strength (double reference_magnetic_field)
 
void start_mag_calibration ()
 Begin the magnetometer calibration routine. More...
 

Private Member Functions

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)
 

Private Attributes

Eigen::MatrixXd A_
 
Eigen::MatrixXd b_
 
bool calibrating_
 whether a temperature calibration is in progress More...
 
double calibration_time_
 seconds to record data for temperature compensation More...
 
bool first_time_
 waiting for first measurement for calibration More...
 
double inlier_thresh_
 threshold to consider measurement an inlier in ellipsoidRANSAC More...
 
ros::ServiceServer mag_cal_srv_
 
message_filters::Subscriber< sensor_msgs::MagneticField > mag_subscriber_
 
Eigen::Vector3d measurement_prev_
 
int measurement_skip_
 
int measurement_throttle_
 
EigenSTL::vector_Vector3d measurements_
 
ros::NodeHandle nh_
 
ros::NodeHandle nh_private_
 
ros::ServiceClient param_set_client_
 
int ransac_iters_
 number of ransac iterations to fit ellipsoid to mag measurements More...
 
double reference_field_strength_
 the strength of earth's magnetic field at your location More...
 
double start_time_
 timestamp of first calibration measurement More...
 

Detailed Description

CalibrateMag sensor class.

Definition at line 62 of file mag_cal.h.

Constructor & Destructor Documentation

rosflight::CalibrateMag::CalibrateMag ( )

Definition at line 43 of file mag_cal.cpp.

Member Function Documentation

const double rosflight::CalibrateMag::a11 ( ) const
inline

The const stuff is to make it read-only.

Definition at line 91 of file mag_cal.h.

const double rosflight::CalibrateMag::a12 ( ) const
inline

Definition at line 92 of file mag_cal.h.

const double rosflight::CalibrateMag::a13 ( ) const
inline

Definition at line 93 of file mag_cal.h.

const double rosflight::CalibrateMag::a21 ( ) const
inline

Definition at line 94 of file mag_cal.h.

const double rosflight::CalibrateMag::a22 ( ) const
inline

Definition at line 95 of file mag_cal.h.

const double rosflight::CalibrateMag::a23 ( ) const
inline

Definition at line 96 of file mag_cal.h.

const double rosflight::CalibrateMag::a31 ( ) const
inline

Definition at line 97 of file mag_cal.h.

const double rosflight::CalibrateMag::a32 ( ) const
inline

Definition at line 98 of file mag_cal.h.

const double rosflight::CalibrateMag::a33 ( ) const
inline

Definition at line 99 of file mag_cal.h.

const double rosflight::CalibrateMag::bx ( ) const
inline

Definition at line 100 of file mag_cal.h.

const double rosflight::CalibrateMag::by ( ) const
inline

Definition at line 101 of file mag_cal.h.

const double rosflight::CalibrateMag::bz ( ) const
inline

Definition at line 102 of file mag_cal.h.

void rosflight::CalibrateMag::do_mag_calibration ( )

Definition at line 148 of file mag_cal.cpp.

void rosflight::CalibrateMag::eigSort ( Eigen::MatrixXd &  w,
Eigen::MatrixXd &  v 
)
private

Definition at line 338 of file mag_cal.cpp.

Eigen::MatrixXd rosflight::CalibrateMag::ellipsoidLS ( EigenSTL::vector_Vector3d  meas)
private

Definition at line 389 of file mag_cal.cpp.

Eigen::MatrixXd rosflight::CalibrateMag::ellipsoidRANSAC ( EigenSTL::vector_Vector3d  meas,
int  iters,
double  inlier_thresh 
)
private

Definition at line 198 of file mag_cal.cpp.

Eigen::Vector3d rosflight::CalibrateMag::intersect ( Eigen::Vector3d  r_m,
Eigen::Vector3d  r_e,
Eigen::MatrixXd  Q,
Eigen::MatrixXd  ub,
double  k 
)
private

Definition at line 315 of file mag_cal.cpp.

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 88 of file mag_cal.h.

bool rosflight::CalibrateMag::mag_callback ( const sensor_msgs::MagneticField::ConstPtr &  mag)

set_refence_magnetic_field_strength

Parameters
reference_magnetic_field

Definition at line 159 of file mag_cal.cpp.

void rosflight::CalibrateMag::magCal ( Eigen::MatrixXd  u,
Eigen::MatrixXd &  A,
Eigen::MatrixXd &  bb 
)
private

Definition at line 463 of file mag_cal.cpp.

void rosflight::CalibrateMag::run ( )

Definition at line 61 of file mag_cal.cpp.

bool rosflight::CalibrateMag::set_param ( std::string  name,
double  value 
)
private

Definition at line 506 of file mag_cal.cpp.

void rosflight::CalibrateMag::set_reference_magnetic_field_strength ( double  reference_magnetic_field)

Definition at line 132 of file mag_cal.cpp.

void rosflight::CalibrateMag::start_mag_calibration ( )

Begin the magnetometer calibration routine.

Definition at line 137 of file mag_cal.cpp.

Member Data Documentation

Eigen::MatrixXd rosflight::CalibrateMag::A_
private

Definition at line 115 of file mag_cal.h.

Eigen::MatrixXd rosflight::CalibrateMag::b_
private

Definition at line 115 of file mag_cal.h.

bool rosflight::CalibrateMag::calibrating_
private

whether a temperature calibration is in progress

Definition at line 119 of file mag_cal.h.

double rosflight::CalibrateMag::calibration_time_
private

seconds to record data for temperature compensation

Definition at line 121 of file mag_cal.h.

bool rosflight::CalibrateMag::first_time_
private

waiting for first measurement for calibration

Definition at line 120 of file mag_cal.h.

double rosflight::CalibrateMag::inlier_thresh_
private

threshold to consider measurement an inlier in ellipsoidRANSAC

Definition at line 126 of file mag_cal.h.

ros::ServiceServer rosflight::CalibrateMag::mag_cal_srv_
private

Definition at line 112 of file mag_cal.h.

message_filters::Subscriber<sensor_msgs::MagneticField> rosflight::CalibrateMag::mag_subscriber_
private

Definition at line 110 of file mag_cal.h.

Eigen::Vector3d rosflight::CalibrateMag::measurement_prev_
private

Definition at line 127 of file mag_cal.h.

int rosflight::CalibrateMag::measurement_skip_
private

Definition at line 124 of file mag_cal.h.

int rosflight::CalibrateMag::measurement_throttle_
private

Definition at line 125 of file mag_cal.h.

EigenSTL::vector_Vector3d rosflight::CalibrateMag::measurements_
private

Definition at line 128 of file mag_cal.h.

ros::NodeHandle rosflight::CalibrateMag::nh_
private

Definition at line 107 of file mag_cal.h.

ros::NodeHandle rosflight::CalibrateMag::nh_private_
private

Definition at line 108 of file mag_cal.h.

ros::ServiceClient rosflight::CalibrateMag::param_set_client_
private

Definition at line 113 of file mag_cal.h.

int rosflight::CalibrateMag::ransac_iters_
private

number of ransac iterations to fit ellipsoid to mag measurements

Definition at line 123 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 117 of file mag_cal.h.

double rosflight::CalibrateMag::start_time_
private

timestamp of first calibration measurement

Definition at line 122 of file mag_cal.h.


The documentation for this class was generated from the following files:


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