20 #ifndef ROBOT_CALIBRATION_CALIBRATION_OFFSET_PARSER_H 21 #define ROBOT_CALIBRATION_CALIBRATION_OFFSET_PARSER_H 23 #include <kdl/chain.hpp> 44 bool add(
const std::string name);
50 bool addFrame(
const std::string name,
51 bool calibrate_x,
bool calibrate_y,
bool calibrate_z,
52 bool calibrate_roll,
bool calibrate_pitch,
bool calibrate_yaw);
58 bool set(
const std::string name,
double value);
64 bool setFrame(
const std::string name,
65 double x,
double y,
double z,
66 double roll,
double pitch,
double yaw);
72 bool update(
const double*
const free_params);
75 double get(
const std::string name)
const;
121 #endif // ROBOT_CALIBRATION_CALIBRATION_OFFSET_PARSER_H virtual ~CalibrationOffsetParser()
CalibrationOffsetParser & operator=(const CalibrationOffsetParser &)
bool getFrame(const std::string name, KDL::Frame &offset) const
Get the offset for a frame calibration.
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
std::vector< std::string > parameter_names_
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string getOffsetYAML()
Get all the current offsets as a YAML.
std::vector< std::string > frame_names_
bool initialize(double *free_params)
Initialize the free_params.
std::vector< double > parameter_offsets_
bool add(const std::string name)
Tell the parser we wish to calibrate an active joint or other single parameter.
bool setFrame(const std::string name, double x, double y, double z, double roll, double pitch, double yaw)
Set the values for a frame.
TFSIMD_FORCE_INLINE const tfScalar & x() const
Calibration code lives under this namespace.
TFSIMD_FORCE_INLINE const tfScalar & z() const
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.
std::string updateURDF(const std::string &urdf)
Update the urdf with the new offsets.
bool reset()
Clear free parameters, but retain values for multi-step calirations.
CalibrationOffsetParser()
bool loadOffsetYAML(const std::string &filename)
Load all the current offsets from a YAML.
bool update(const double *const free_params)
Update the offsets based on free_params from ceres-solver.