20 #ifndef ROBOT_CALIBRATION_MODELS_CHAIN_H 21 #define ROBOT_CALIBRATION_MODELS_CHAIN_H 24 #include <kdl/chain.hpp> 25 #include <kdl/tree.hpp> 28 #include <geometry_msgs/PointStamped.h> 29 #include <sensor_msgs/JointState.h> 30 #include <robot_calibration_msgs/CalibrationData.h> 125 virtual std::vector<geometry_msgs::PointStamped>
project(
126 const robot_calibration_msgs::CalibrationData& data,
134 const sensor_msgs::JointState& state);
136 std::string
name()
const;
160 #endif // ROBOT_CALIBRATION_MODELS_CHAIN_H virtual std::vector< geometry_msgs::PointStamped > project(const robot_calibration_msgs::CalibrationData &data, const CalibrationOffsetParser &offsets)
Compute the position of the estimated points.
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
ChainModel(const std::string &name, KDL::Tree model, std::string root, std::string tip)
Create a new chain model.
KDL::Frame getChainFK(const CalibrationOffsetParser &offsets, const sensor_msgs::JointState &state)
Compute the forward kinematics of the chain, based on the offsets and the joint positions of the stat...
Calibration code lives under this namespace.
void axis_magnitude_from_rotation(const KDL::Rotation &r, double &x, double &y, double &z)
Converts from KDL::Rotation to angle-axis-with-integrated-magnitude.
KDL::Rotation rotation_from_axis_magnitude(const double x, const double y, const double z)
Converts our angle-axis-with-integrated-magnitude representation to a KDL::Rotation.
Model of a kinematic chain. This is the basic instance where we transform the world observations into...