Class Chain3dModel
- Defined in File chain3d.hpp 
Inheritance Relationships
Derived Types
- public robot_calibration::Camera2dModel(Class Camera2dModel)
- public robot_calibration::Camera3dModel(Class Camera3dModel)
Class Documentation
- 
class Chain3dModel
- Model of a kinematic chain. This is the basic instance where we transform the world observations into the proper root frame. - Each world observation is an estimated point in some frame. In the case of the four led gripper, each led has an absolutely known location in the gripper_led_frame. The ordering of the points is: When using a checkerboard, each interesection on the checkerboard is an observation point. Even though checkerboard should be flat, the code assumes that each checkerboard intersection has 3 degrees of translational freedom. The gripper_led_frame to checkerboard_frame transformation becomes a set of free parameters in the calibration. - Based on the 6x5 checkboard, the ordering of the oberservation points produced by the OpenCV chessboard finder is always the same: - Subclassed by robot_calibration::Camera2dModel, robot_calibration::Camera3dModel - Public Functions - 
Chain3dModel(const std::string &name, KDL::Tree model, std::string root, std::string tip)
- Create a new chain model. - Parameters:
- model – The KDL model of the robot’s kinematics. 
- root – The name of the root link, must be consistent across all models used for error modeling. Usually ‘base_link’. 
- tip – The tip of the chain. 
 
 
 - 
inline virtual ~Chain3dModel()
 - 
virtual std::vector<geometry_msgs::msg::PointStamped> project(const robot_calibration_msgs::msg::CalibrationData &data, const OptimizationOffsets &offsets)
- Compute the position of the estimated points. - Parameters:
- data – The calibration data for this observation. 
- offsets – The offsets that the solver wants to examine. 
 
 
 - 
KDL::Frame getChainFK(const OptimizationOffsets &offsets, const sensor_msgs::msg::JointState &state)
- Compute the forward kinematics of the chain, based on the offsets and the joint positions of the state message. 
 - 
virtual std::string getName() const
- Get the name of this model (as provided in the YAML config) 
 - 
virtual std::string getType() const
- Get the type of this model. 
 
- 
Chain3dModel(const std::string &name, KDL::Tree model, std::string root, std::string tip)