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. | |
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. | |
CalibrationOffsetParser () | |
double | get (const std::string name) const |
Get the offset. | |
bool | getFrame (const std::string name, KDL::Frame &offset) const |
Get the offset for a frame calibration. | |
std::string | getOffsetYAML () |
Get all the current offsets as a YAML. | |
int | size () |
bool | update (const double *const free_params) |
Update the offsets based on free_params from ceres-solver. | |
std::string | updateURDF (const std::string &urdf) |
Update the urdf with the new offsets. | |
virtual | ~CalibrationOffsetParser () |
Private Member Functions | |
CalibrationOffsetParser (const CalibrationOffsetParser &) | |
CalibrationOffsetParser & | operator= (const CalibrationOffsetParser &) |
Private Attributes | |
std::vector< std::string > | frame_names_ |
std::vector< std::string > | parameter_names_ |
std::vector< double > | parameter_offsets_ |
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 32 of file calibration_offset_parser.h.
Definition at line 30 of file calibration_offset_parser.cpp.
virtual robot_calibration::CalibrationOffsetParser::~CalibrationOffsetParser | ( | ) | [inline, virtual] |
Definition at line 36 of file calibration_offset_parser.h.
robot_calibration::CalibrationOffsetParser::CalibrationOffsetParser | ( | const CalibrationOffsetParser & | ) | [private] |
bool robot_calibration::CalibrationOffsetParser::add | ( | const std::string | name | ) |
Tell the parser we wish to calibrate an active joint or other single parameter.
joint_name | The name of the joint, e.g. "shoulder_pan_joint" |
Definition at line 35 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.
name | The name of the fixed joint, e.g. "head_camera_rgb_joint" |
Definition at line 42 of file calibration_offset_parser.cpp.
double robot_calibration::CalibrationOffsetParser::get | ( | const std::string | name | ) | const |
Get the offset.
Definition at line 74 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.
name | The name of the fixed joint, e.g. "head_camera_rgb_joint" |
offset | The KDL::Frame to fill in the offset. |
Definition at line 85 of file calibration_offset_parser.cpp.
std::string robot_calibration::CalibrationOffsetParser::getOffsetYAML | ( | ) |
Get all the current offsets as a YAML.
Definition at line 118 of file calibration_offset_parser.cpp.
CalibrationOffsetParser& robot_calibration::CalibrationOffsetParser::operator= | ( | const CalibrationOffsetParser & | ) | [private] |
Definition at line 113 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 67 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 128 of file calibration_offset_parser.cpp.
std::vector<std::string> robot_calibration::CalibrationOffsetParser::frame_names_ [private] |
Definition at line 82 of file calibration_offset_parser.h.
std::vector<std::string> robot_calibration::CalibrationOffsetParser::parameter_names_ [private] |
Definition at line 79 of file calibration_offset_parser.h.
std::vector<double> robot_calibration::CalibrationOffsetParser::parameter_offsets_ [private] |
Definition at line 85 of file calibration_offset_parser.h.