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>
|
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 () |
|
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.
robot_calibration::CalibrationOffsetParser::CalibrationOffsetParser |
( |
| ) |
|
virtual robot_calibration::CalibrationOffsetParser::~CalibrationOffsetParser |
( |
| ) |
|
|
inlinevirtual |
bool robot_calibration::CalibrationOffsetParser::add |
( |
const std::string |
name | ) |
|
Tell the parser we wish to calibrate an active joint or other single parameter.
- Parameters
-
name | The 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
-
name | The 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 |
bool robot_calibration::CalibrationOffsetParser::getFrame |
( |
const std::string |
name, |
|
|
KDL::Frame & |
offset |
|
) |
| const |
Get the offset for a frame calibration.
- Parameters
-
name | The name of the fixed joint, e.g. "head_camera_rgb_joint" |
offset | The 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 |
( |
| ) |
|
bool robot_calibration::CalibrationOffsetParser::initialize |
( |
double * |
free_params | ) |
|
bool robot_calibration::CalibrationOffsetParser::loadOffsetYAML |
( |
const std::string & |
filename | ) |
|
bool robot_calibration::CalibrationOffsetParser::reset |
( |
| ) |
|
bool robot_calibration::CalibrationOffsetParser::set |
( |
const std::string |
name, |
|
|
double |
value |
|
) |
| |
Set the values for a single parameter.
- Parameters
-
name | The 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
-
name | The 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 |
( |
| ) |
|
bool robot_calibration::CalibrationOffsetParser::update |
( |
const double *const |
free_params | ) |
|
std::string robot_calibration::CalibrationOffsetParser::updateURDF |
( |
const std::string & |
urdf | ) |
|
std::vector<std::string> robot_calibration::CalibrationOffsetParser::frame_names_ |
|
private |
size_t robot_calibration::CalibrationOffsetParser::num_free_params_ |
|
private |
std::vector<std::string> robot_calibration::CalibrationOffsetParser::parameter_names_ |
|
private |
std::vector<double> robot_calibration::CalibrationOffsetParser::parameter_offsets_ |
|
private |
The documentation for this class was generated from the following files: