Public Types | Public Member Functions

TRTK::RansacPivotCalibrationModel< T > Class Template Reference

This class implements the Ransac::Model interface for all PivotCalibration classes. More...

#include <RansacPivotCalibrationModel.hpp>

Inheritance diagram for TRTK::RansacPivotCalibrationModel< T >:
Collaboration diagram for TRTK::RansacPivotCalibrationModel< T >:

List of all members.

Public Types

typedef T value_type
typedef PivotCalibration< T >
::Vector3T 
Vector3T
typedef PivotCalibration< T >
::Matrix3T 
Matrix3T
typedef PivotCalibration< T >
::DataType 
DataType

Public Member Functions

 RansacPivotCalibrationModel (PivotCalibration< T > &estimator)
 Constructs an instance of RansacPivotCalibrationModel.
void compute ()
 Estimates the model parameters.
getDeviation (const DataType &datum) const
 Returns the amount of how much a datum deviates from the model.
unsigned getMinimumNumberOfItems () const
 Returns the minimum number of items required to compute the model.
getRMSE () const
 Returns the root mean square error of the estimated regression model.
void setData (const std::vector< DataType > &data)
 Sets the sample data.
void setEstimator (PivotCalibration< T > &estimator)
 Sets the pivot calibration instance.
virtual T getDeviation (const DataType &datum) const =0
 Return the amount of how much a datum deviates from the model.
virtual void setData (const std::vector< DataType > &data)=0
 Set the sample data. No data is copied but a reference is stored.

Detailed Description

template<class T>
class TRTK::RansacPivotCalibrationModel< T >

This class implements the Ransac::Model interface for all PivotCalibration classes.

Template Parameters:
TScalar type (must be a floating point).

Here is an example that shows how to use this class:

 #include <cmath>
 #include <cstdlib>
 #include <iostream>
 #include <iomanip>
 #include <utility>
 #include <vector>
 
 #include<Eigen/StdVector>
 
 #include <TRTK/Clock.hpp>
 #include <TRTK/Coordinate.hpp>
 #include <TRTK/Tools.hpp>
 #include <TRTK/Transform3D.hpp>
 #include <TRTK/PivotCalibration.hpp>
 #include <TRTK/RansacPivotCalibrationModel.hpp>
 
 
 using namespace std;
 using namespace TRTK;
 using namespace TRTK::Tools;
 
 double pi = 3.1415926535;
 
 typedef PivotCalibration<double> Calibration;
 typedef Calibration::value_type value_type;
 typedef Calibration::Matrix3T Matrix;
 typedef Calibration::Vector3T Vector;
 
 
 namespace
 {
 
     struct GenerateTestData
     {
         GenerateTestData(double sigma = 0)
         {
             // Generate some (noisy) test data.
 
             // We assume, there is a tool which is aligned with the x-axis. Its tool
             // tip is located at the (global) point p (pivot point), and the center of
             // the tool coordinate system is located at the point t. The local tool tip
             // position is defined to be (a, 0, 0).
             //
             // The relation between the local coordinate system and the global coordinate
             // system is given by p_global = R * p_local + t. The initial rotation R of
             // the tool coordinate system is a rotation of pi/2 in the x-y plane.
             //
             // Now the tool is rotated, where the tool tip remains at the same position.
 
             Matrix R;
             R << cos(pi/2), -sin(pi/2), 0,
                  sin(pi/2),  cos(pi/2), 0,
                          0,          0, 1;
 
             double a = 70;
             p_local = Vector(a, 0, 0);
             p = Vector(1, 1, 1);
             Vector t = p - R * p_local;
 
             for (double theta = -0.8 * pi / 2; theta < 0.8 * pi / 2; theta += pi / 20)
             {
                 for (double phi = -0.8 * pi / 2; phi < 0.8 * pi / 2; phi += pi / 20)
                 {
                     // Rotate around pivot point P.
 
                     const double x = p.x();
                     const double y = p.y();
                     const double z = p.z();
 
                     Transform3D<double> transform;
                     transform.translate(-x, -y, -z).rotateZ(phi).rotateY(theta).translate(x, y, z);
 
                     Vector location = transform * t;
                     Matrix rotation = transform.getTransformationMatrix().block(0, 0, 3, 3) * R;
 
                     // Add some noise
 
                     using TRTK::Tools::randn;
                     location += sigma * Vector(randn(), randn(), randn());
 
                     // Store the results
 
                     locations.push_back(location);
                     rotations.push_back(rotation);
                 }
             }
         }
 
         vector<Matrix> rotations;
         vector<Vector> locations;
         Vector p;
         Vector p_local;
     };
 
 } // end of anonymous namespace
 
 
 int main()
 {
     cout << setprecision(4);
     cout << fixed;
 
     cout << "Pivot calibration example" << endl;
     cout << "-------------------------" << endl << endl;
 
     GenerateTestData test_data;
     cout << "Ground truth" << endl;
     cout << "Pivot point: " << test_data.p.transpose() << endl;
     cout << "Local pivot point: " << test_data.p_local.transpose() << endl << endl << endl;
 
     {
         Clock clock;
         srand(0);
         GenerateTestData test_data;
 
         PivotCalibrationTwoStep<double> calibration;
         calibration.setLocations(make_range(test_data.locations));
         calibration.setRotations(make_range(test_data.rotations));
         double rmse = calibration.compute();
 
         cout << "No noise" << endl;
         cout << "RMSE: " << rmse << endl;
         cout << "Global pivot point: " << calibration.getPivotPoint().transpose() << "\t";
         cout << "Error: " << (calibration.getPivotPoint() - test_data.p).norm() << endl;
         cout << "Local pivot point: " << calibration.getLocalPivotPoint().transpose() << "\t";
         cout << "Error: " << (calibration.getLocalPivotPoint() - test_data.p_local).norm() << endl;
         cout << clock << endl;
     }
 
     {
         Clock clock;
         srand(0);
         GenerateTestData test_data(0.1);
 
         PivotCalibrationTwoStep<double> calibration;
         calibration.setLocations(make_range(test_data.locations));
         calibration.setRotations(make_range(test_data.rotations));
         double rmse = calibration.compute();
 
         cout << "With noise" << endl;
         cout << "RMSE: " << rmse << endl;
         cout << "Global pivot point: " << calibration.getPivotPoint().transpose() << "\t";
         cout << "Error: " << (calibration.getPivotPoint() - test_data.p).norm() << endl;
         cout << "Local pivot point: " << calibration.getLocalPivotPoint().transpose() << "\t";
         cout << "Error: " << (calibration.getLocalPivotPoint() - test_data.p_local).norm() << endl;
         cout << clock << endl;
     }
 
     {
         Clock clock;
         srand(0);
         GenerateTestData test_data(0.1);
         vector<pair<Vector, Matrix> > data = zip(test_data.locations, test_data.rotations);
 
         PivotCalibrationTwoStep<double> calibration;
         RansacPivotCalibrationModel<double> model(calibration);
         Ransac<double, PivotCalibration<double>::DataType> ransac;
 
         ransac.setModel(model);
         ransac.setData(data);
         ransac.setErrorTolerance(0.2);
 
         unsigned number_of_samples_used = ransac.compute();
 
         cout << "RANSAC and noise" << endl;
         cout << "RMSE: " << model.getRMSE() << endl;
         cout << "Number of samples used: " << number_of_samples_used << endl;
         cout << "Global pivot point: " << calibration.getPivotPoint().transpose() << "\t";
         cout << "Error: " << (calibration.getPivotPoint() - test_data.p).norm() << endl;
         cout << "Local pivot point: " << calibration.getLocalPivotPoint().transpose() << "\t";
         cout << "Error: " << (calibration.getLocalPivotPoint() - test_data.p_local).norm() << endl;
         cout << clock << endl;
     }
 
     return 0;
 }

Output:

  * Pivot calibration example
  * -------------------------
  * 
  * Ground truth
  * Pivot point: 1.0000 1.0000 1.0000
  * Local pivot point: 70.0000  0.0000  0.0000
  * 
  * 
  * No noise
  * RMSE: 0.0000
  * Global pivot point: 1.0000 1.0000 1.0000        Error: 0.0000
  * Local pivot point: 70.0000 -0.0000  0.0000      Error: 0.0000
  * Elapsed time: 0.0390 seconds.
  * 
  * With noise
  * RMSE: 0.1752
  * Global pivot point: 0.9918 1.0086 1.0184        Error: 0.0219
  * Local pivot point: 70.0125  0.0018  0.0190      Error: 0.0228
  * Elapsed time: 0.0350 seconds.
  * 
  * RANSAC and noise
  * RMSE: 0.1320
  * Number of samples used: 202
  * Global pivot point: 0.9856 1.0058 1.0158        Error: 0.0221
  * Local pivot point: 70.0144  0.0271  0.0202      Error: 0.0368
  * Elapsed time: 0.6570 seconds.
* 

For further information, please have a look at the documentation of the particular Pivot calibration class and the Ransac class, respectively.

See also:
Ransac, Ransac::Model, PivotCalibration
Author:
Christoph Haenisch
Version:
0.1.0
Date:
last changed on 2016-07-25

Definition at line 259 of file RansacPivotCalibrationModel.hpp.


Constructor & Destructor Documentation

template<class T >
TRTK::RansacPivotCalibrationModel< T >::RansacPivotCalibrationModel ( PivotCalibration< T > &  estimator )

Constructs an instance of RansacPivotCalibrationModel.

Parameters:
[in]modelA fitting class.

Definition at line 290 of file RansacPivotCalibrationModel.hpp.


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