Public Member Functions | Protected Attributes | Private Attributes | List of all members
robot_calibration::ChainModel Class Reference

Model of a kinematic chain. This is the basic instance where we transform the world observations into the proper root frame. More...

#include <chain.h>

Inheritance diagram for robot_calibration::ChainModel:
Inheritance graph
[legend]

Public Member Functions

 ChainModel (const std::string &name, KDL::Tree model, std::string root, std::string tip)
 Create a new chain model. More...
 
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 state message. More...
 
virtual std::string getName () const
 Get the name of this model (as provided in the YAML config) More...
 
virtual std::string getType () const
 Get the type of this model. More...
 
virtual std::vector< geometry_msgs::PointStamped > project (const robot_calibration_msgs::CalibrationData &data, const CalibrationOffsetParser &offsets)
 Compute the position of the estimated points. More...
 
virtual ~ChainModel ()
 

Protected Attributes

std::string name_
 
std::string root_
 
std::string tip_
 

Private Attributes

KDL::Chain chain_
 

Detailed Description

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:

       _                   _
      | |                 | |
      | |                 | |
      | |                 | |
      | |                 | |
      | |                 | |
      | |     gripper     | |
      |---------------------|
      |                     |
      |    0           3    |
      |                     |
      |          X <------------ gripper_led_frame
      |                     |
      |    2           1    |
      |                     |
       \___________________/

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:

   ____________________________
  |                            |
  |  ###   ###   ###   ###     |
  |  ###   ###   ###   ###     |
  |  ###   ###   ###  LL##     |    11  First Observation Point
  |     ###   ###   ##LL  ###  |    11
  |     ###   ###   ###   ###  |
  |     ###   ###   ###   ###  |    22  Second Observation Point
  |  ###   ###   ###   ###     |    22
  |  ###   ###   ###   ###     |
  |  ##22  ###   ###   ###     |    LL  Last (20th) Obervation Point
  |    22##   ###   ###   ###  |    LL
  |     ###   ###   ###   ###  |
  |    11##   ###   ###   ###  |
  |  ##11  ###   ###   ###     |
  |  ###   ###   ###   ###     |   gripper_link
  |  ###   ###   ###   ###     |      X-axis (increasing row)
  |                            |     ^
  |           _____            |     |     gripper_link
  |          |     |           |     |  ----> Z-axis (increasing col)
  |          |     |
  |          |  0<----- gripper_link frame origin
  |__________|     |___________
             |     |
          ___|_____|___
         |             |
         |   Gripper   |
         |             |

For the ideal checkboard:

Definition at line 107 of file chain.h.

Constructor & Destructor Documentation

◆ ChainModel()

robot_calibration::ChainModel::ChainModel ( const std::string &  name,
KDL::Tree  model,
std::string  root,
std::string  tip 
)

Create a new chain model.

Parameters
modelThe KDL model of the robot's kinematics.
rootThe name of the root link, must be consistent across all models used for error modeling. Usually 'base_link'.
tipThe tip of the chain.

Definition at line 41 of file models.cpp.

◆ ~ChainModel()

virtual robot_calibration::ChainModel::~ChainModel ( )
inlinevirtual

Definition at line 118 of file chain.h.

Member Function Documentation

◆ getChainFK()

KDL::Frame robot_calibration::ChainModel::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 state message.

Definition at line 117 of file models.cpp.

◆ getName()

std::string robot_calibration::ChainModel::getName ( ) const
virtual

Get the name of this model (as provided in the YAML config)

Definition at line 152 of file models.cpp.

◆ getType()

std::string robot_calibration::ChainModel::getType ( ) const
virtual

Get the type of this model.

Reimplemented in robot_calibration::Camera3dModel.

Definition at line 157 of file models.cpp.

◆ project()

std::vector< geometry_msgs::PointStamped > robot_calibration::ChainModel::project ( const robot_calibration_msgs::CalibrationData &  data,
const CalibrationOffsetParser offsets 
)
virtual

Compute the position of the estimated points.

Parameters
dataThe calibration data for this observation.
offsetsThe offsets that the solver wants to examine.

Reimplemented in robot_calibration::Camera3dModel.

Definition at line 53 of file models.cpp.

Member Data Documentation

◆ chain_

KDL::Chain robot_calibration::ChainModel::chain_
private

Definition at line 147 of file chain.h.

◆ name_

std::string robot_calibration::ChainModel::name_
protected

Definition at line 152 of file chain.h.

◆ root_

std::string robot_calibration::ChainModel::root_
protected

Definition at line 150 of file chain.h.

◆ tip_

std::string robot_calibration::ChainModel::tip_
protected

Definition at line 151 of file chain.h.


The documentation for this class was generated from the following files:


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01