Public Member Functions | Private Member Functions | Private Attributes | List of all members
robot_calibration::CalibrationOffsetParser Class Reference

Combined parser and configuration for calibration offsets. Holds the configuration of what is to be calibrated, and and parses the actual adjustments from the free parameters. More...

#include <calibration_offset_parser.h>

Public Member Functions

bool add (const std::string name)
 Tell the parser we wish to calibrate an active joint or other single parameter. More...
 
bool addFrame (const std::string name, bool calibrate_x, bool calibrate_y, bool calibrate_z, bool calibrate_roll, bool calibrate_pitch, bool calibrate_yaw)
 Tell the parser we wish to calibrate a fixed joint. More...
 
 CalibrationOffsetParser ()
 
double get (const std::string name) const
 Get the offset. More...
 
bool getFrame (const std::string name, KDL::Frame &offset) const
 Get the offset for a frame calibration. More...
 
std::string getOffsetYAML ()
 Get all the current offsets as a YAML. More...
 
bool initialize (double *free_params)
 Initialize the free_params. More...
 
bool loadOffsetYAML (const std::string &filename)
 Load all the current offsets from a YAML. More...
 
bool reset ()
 Clear free parameters, but retain values for multi-step calirations. More...
 
bool set (const std::string name, double value)
 Set the values for a single parameter. More...
 
bool setFrame (const std::string name, double x, double y, double z, double roll, double pitch, double yaw)
 Set the values for a frame. More...
 
size_t size ()
 
bool update (const double *const free_params)
 Update the offsets based on free_params from ceres-solver. More...
 
std::string updateURDF (const std::string &urdf)
 Update the urdf with the new offsets. More...
 
virtual ~CalibrationOffsetParser ()
 

Private Member Functions

 CalibrationOffsetParser (const CalibrationOffsetParser &)
 
CalibrationOffsetParseroperator= (const CalibrationOffsetParser &)
 

Private Attributes

std::vector< std::string > frame_names_
 
size_t num_free_params_
 
std::vector< std::string > parameter_names_
 
std::vector< double > parameter_offsets_
 

Detailed Description

Combined parser and configuration for calibration offsets. Holds the configuration of what is to be calibrated, and and parses the actual adjustments from the free parameters.

Definition at line 33 of file calibration_offset_parser.h.

Constructor & Destructor Documentation

robot_calibration::CalibrationOffsetParser::CalibrationOffsetParser ( )

Definition at line 32 of file calibration_offset_parser.cpp.

virtual robot_calibration::CalibrationOffsetParser::~CalibrationOffsetParser ( )
inlinevirtual

Definition at line 37 of file calibration_offset_parser.h.

robot_calibration::CalibrationOffsetParser::CalibrationOffsetParser ( const CalibrationOffsetParser )
private

Member Function Documentation

bool robot_calibration::CalibrationOffsetParser::add ( const std::string  name)

Tell the parser we wish to calibrate an active joint or other single parameter.

Parameters
nameThe name of the joint, e.g. "shoulder_pan_joint"

Definition at line 37 of file calibration_offset_parser.cpp.

bool robot_calibration::CalibrationOffsetParser::addFrame ( const std::string  name,
bool  calibrate_x,
bool  calibrate_y,
bool  calibrate_z,
bool  calibrate_roll,
bool  calibrate_pitch,
bool  calibrate_yaw 
)

Tell the parser we wish to calibrate a fixed joint.

Parameters
nameThe name of the fixed joint, e.g. "head_camera_rgb_joint"

Definition at line 66 of file calibration_offset_parser.cpp.

double robot_calibration::CalibrationOffsetParser::get ( const std::string  name) const

Get the offset.

Definition at line 139 of file calibration_offset_parser.cpp.

bool robot_calibration::CalibrationOffsetParser::getFrame ( const std::string  name,
KDL::Frame offset 
) const

Get the offset for a frame calibration.

Parameters
nameThe name of the fixed joint, e.g. "head_camera_rgb_joint"
offsetThe KDL::Frame to fill in the offset.
Returns
True if there is an offset to apply, false if otherwise.

Definition at line 150 of file calibration_offset_parser.cpp.

std::string robot_calibration::CalibrationOffsetParser::getOffsetYAML ( )

Get all the current offsets as a YAML.

Definition at line 210 of file calibration_offset_parser.cpp.

bool robot_calibration::CalibrationOffsetParser::initialize ( double *  free_params)

Initialize the free_params.

Definition at line 125 of file calibration_offset_parser.cpp.

bool robot_calibration::CalibrationOffsetParser::loadOffsetYAML ( const std::string &  filename)

Load all the current offsets from a YAML.

Definition at line 189 of file calibration_offset_parser.cpp.

CalibrationOffsetParser& robot_calibration::CalibrationOffsetParser::operator= ( const CalibrationOffsetParser )
private
bool robot_calibration::CalibrationOffsetParser::reset ( )

Clear free parameters, but retain values for multi-step calirations.

Definition at line 183 of file calibration_offset_parser.cpp.

bool robot_calibration::CalibrationOffsetParser::set ( const std::string  name,
double  value 
)

Set the values for a single parameter.

Parameters
nameThe name of the joint, e.g. "shoulder_pan_joint"

Definition at line 91 of file calibration_offset_parser.cpp.

bool robot_calibration::CalibrationOffsetParser::setFrame ( const std::string  name,
double  x,
double  y,
double  z,
double  roll,
double  pitch,
double  yaw 
)

Set the values for a frame.

Parameters
nameThe name of the fixed joint, e.g. "head_camera_rgb_joint"

Definition at line 104 of file calibration_offset_parser.cpp.

size_t robot_calibration::CalibrationOffsetParser::size ( )
Returns
The number of free parameters being parsed

Definition at line 178 of file calibration_offset_parser.cpp.

bool robot_calibration::CalibrationOffsetParser::update ( const double *const  free_params)

Update the offsets based on free_params from ceres-solver.

Definition at line 132 of file calibration_offset_parser.cpp.

std::string robot_calibration::CalibrationOffsetParser::updateURDF ( const std::string &  urdf)

Update the urdf with the new offsets.

Definition at line 220 of file calibration_offset_parser.cpp.

Member Data Documentation

std::vector<std::string> robot_calibration::CalibrationOffsetParser::frame_names_
private

Definition at line 106 of file calibration_offset_parser.h.

size_t robot_calibration::CalibrationOffsetParser::num_free_params_
private

Definition at line 112 of file calibration_offset_parser.h.

std::vector<std::string> robot_calibration::CalibrationOffsetParser::parameter_names_
private

Definition at line 103 of file calibration_offset_parser.h.

std::vector<double> robot_calibration::CalibrationOffsetParser::parameter_offsets_
private

Definition at line 109 of file calibration_offset_parser.h.


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


robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30