Public Types | Public Member Functions

TRTK::PivotCalibration< T > Class Template Reference

This is the common interface for all pivot-point-calibration classes. More...

#include <PivotCalibration.hpp>

Inheritance diagram for TRTK::PivotCalibration< T >:

List of all members.

Public Types

enum  Error { NOT_ENOUGH_INPUT_DATA, UNEQUAL_CARDINALITY_OF_INPUT_SETS, UNKNOWN_ERROR }
typedef T value_type
typedef Eigen::Matrix< T, 3, 1 > Vector3T
typedef Eigen::Matrix< T, 4, 1 > Vector4T
typedef Eigen::Matrix< T,
Eigen::Dynamic, 1 > 
VectorXT
typedef Eigen::Matrix< T, 3, 3 > Matrix3T
typedef Eigen::Matrix< T, 4, 4 > Matrix4T
typedef Eigen::Matrix< T,
Eigen::Dynamic, Eigen::Dynamic > 
MatrixXT
typedef Coordinate< T > Point
typedef std::pair< Vector3T,
Matrix3T > 
DataType

Public Member Functions

virtual size_t getNumberItemsRequired () const =0
 Returns the minimum number of locations and rotations needed for the algorithm.
virtual void setLocations (Range< Vector3T > locations)=0
virtual void setRotations (Range< Matrix3T > rotations)=0
virtual T compute ()=0
 Returns the RMSE.
virtual T getRMSE () const =0
 Returns the RMSE of the last computation.
virtual const Vector3T & getLocalPivotPoint () const =0
 Returns the pivot point (or tool tip) in local coordinates.
virtual const Vector3T & getPivotPoint () const =0
 Returns the pivot point (or tool tip) in world coordinates.

Detailed Description

template<class T>
class TRTK::PivotCalibration< T >

This is the common interface for all pivot-point-calibration classes.

Template Parameters:
Tscalar (floating point) type

A pivot-point-calibration is a procedure that aims at finding a global and local pivot point of a rigid structure whose motion is constrained in such a way that it moves around a pivot point. If the structure is equipped with a localization sensor (i.e. if it is tracked) the pivot point can be determined in the global tracker coordinate system and the local structure's coordinate system. Typical examples of application include the tool tip calibration or the hip center determination.

The calibration procedure to obtain a tool tip location is as follows: The tool tip is placed in a divot and the tool is moved around this pivot point while always touching the divot with its tip. The location as well as the rotation of the sensor system is saved for each sampling instance. Then this list is passed to one of the pivot calibration algorithms and the sought location/translation is computed.

Tool Tip Calibration (small).png

Movement of a tool while recording data for the tool tip calibration.

Given a new measurement of the tracker (which comprises the position \( t_i \) and orientation \( R_i \) of the sensor in the global coordinate system) the pivot point the tool tip location in global coordinates can be easily computed as \( p_{global} = R_i p_{local} + t_i \).

Note:
We always assume, that the transformations map from a local coordinate system to the global coordinate system. That is, given a rotation matrix \( R \) and a translation vector \( t \) describing the orientation and the location of a sensor system, respectively, the vector \( p' \) in global coordinates corresponds to the vector \( p \) in local coordinates by this relation:

\[ p' = Rp + t \]

Note:
You might also be interested in the RANSAC interface class TRTK::RansacPivotCalibrationModel. Especially, if you expect outliers in your measurements.
Example:

Here is an example of how to perform a pivot calibration:

 typedef TRTK::PivotCalibration<double> Calibration;
 typedef TRTK::Calibration::Matrix3T Matrix;
 typedef TRTK::Calibration::Vector3T Vector;

 // These rotation matrices and translation vectors describe the local
 // sensor coordinate systems in global coordinates

 std::vector<Matrix> rotations;
 std::vector<Vector> locations;

 while (true)
 {
     // record the data and break if enough data was collected

     // ...

     // save the rotation matrix and the translation vector...

     Matrix R;
     R << r11, r12, r13, r21, r22, r23, r31, r32, r33;

     Vector t(t1, t2, t3);

     rotations.push_back(R);
     locations.push_back(t);
 }

 PivotCalibrationTwoStep<double> calibration;
 calibration.setRotations(make_range(test_data.rotations));
 calibration.setLocations(make_range(test_data.locations));
 double rmse = calibration.compute();

 Vector local_pivot_point = calibration.getLocalPivotPoint();

 // ...

 // Determinte the current tool tip position in global coordinates.
 Vector tool_tip_position = current_rotation * local_pivot_point + current_position;
Note:
See http://eigen.tuxfamily.org/ for how to use the Matrix class.
See also:
TRTK::PivotCalibrationCombinatorialApproach, TRTK::PivotCalibrationLeastSquares, TRTK::PivotCalibrationPATM, TRTK::PivotCalibrationTwoStep, TRTK::RansacPivotCalibrationModel, TRTK::Coordinate and TRTK::Transform3D
Author:
Christoph Haenisch
Version:
1.0.0
Date:
last changed on 2016-07-25

Definition at line 144 of file PivotCalibration.hpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines