Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | List of all members
grl::HandEyeCalibrationVrepPlugin Class Reference

#include <HandEyeCalibrationVrepPlugin.hpp>

+ Inheritance diagram for grl::HandEyeCalibrationVrepPlugin:
+ Collaboration diagram for grl::HandEyeCalibrationVrepPlugin:

Public Types

enum  ParamIndex { RobotBaseName, RobotTipName, OpticalTrackerBaseName, OpticalTrackerDetectedObjectName }
 
typedef std::tuple< std::string, std::string, std::string, std::string > Params
 

Public Member Functions

void addFrame ()
 
void applyEstimate ()
 Will apply the stored estimate to the v-rep simulation value. More...
 
void construct ()
 
void estimateHandEyeScrew ()
 run solver to estimate the unknown transform and set the simulation to the estimated value More...
 
Eigen::Affine3d getEstimate ()
 
 HandEyeCalibrationVrepPlugin (Params params=defaultParams())
 
void restoreSensorPosition ()
 Correct modified transform for measured optical tracker data. More...
 

Static Public Member Functions

static const Params defaultParams ()
 

Static Public Attributes

static const bool debug = false
 

Detailed Description

Creates a complete vrep plugin object usage:

auto handEyeCalib = std::make_shared<grl::HandEyeCalibrationVrepPlugin>();
handEyeCalib->construct();
// move objects to new position
Todo:

this implementation is a bit hacky, redesign it

separate out grl specific code from general kuka control code

Template on robot driver and create a driver that just reads/writes to/from the simulation, then pass the two templates so the simulation and the real driver can be selected.

Definition at line 47 of file HandEyeCalibrationVrepPlugin.hpp.

Member Typedef Documentation

§ Params

typedef std::tuple< std::string, std::string, std::string, std::string > grl::HandEyeCalibrationVrepPlugin::Params
Todo:
allow default params

Definition at line 65 of file HandEyeCalibrationVrepPlugin.hpp.

Member Enumeration Documentation

§ ParamIndex

Enumerator
RobotBaseName 

V-REP handle string for the base of the first known transform, often a robot base.

RobotTipName 

V-REP handle string for the tip of the first known transform, often a robot tip.

OpticalTrackerBaseName 

V-REP handle string for the tip of the first known transform, often a robot tip.

OpticalTrackerDetectedObjectName 

Definition at line 52 of file HandEyeCalibrationVrepPlugin.hpp.

Constructor & Destructor Documentation

§ HandEyeCalibrationVrepPlugin()

grl::HandEyeCalibrationVrepPlugin::HandEyeCalibrationVrepPlugin ( Params  params = defaultParams())
inline
Todo:
allow KukaFRIThreadSeparator parameters to be updated
Todo:
figure out how to re-enable when .so isn't loaded

Definition at line 78 of file HandEyeCalibrationVrepPlugin.hpp.

Member Function Documentation

§ addFrame()

void grl::HandEyeCalibrationVrepPlugin::addFrame ( )
inline

Definition at line 99 of file HandEyeCalibrationVrepPlugin.hpp.

§ applyEstimate()

void grl::HandEyeCalibrationVrepPlugin::applyEstimate ( )
inline

Will apply the stored estimate to the v-rep simulation value.

A default transform is saved when construct() was called so if no estimate has been found that will be used.

Definition at line 189 of file HandEyeCalibrationVrepPlugin.hpp.

§ construct()

void grl::HandEyeCalibrationVrepPlugin::construct ( )
inline

construct() function completes initialization of the plugin

Todo:
move this into the actual constructor, but need to correctly handle or attach vrep shared libraries for unit tests.

Definition at line 91 of file HandEyeCalibrationVrepPlugin.hpp.

§ defaultParams()

static const Params grl::HandEyeCalibrationVrepPlugin::defaultParams ( )
inlinestatic

Definition at line 68 of file HandEyeCalibrationVrepPlugin.hpp.

§ estimateHandEyeScrew()

void grl::HandEyeCalibrationVrepPlugin::estimateHandEyeScrew ( )
inline

run solver to estimate the unknown transform and set the simulation to the estimated value

after calling addFrame a number of times in different positions and orientations

Todo:

probably want to run at least part of this in a separate thread.

evaluate if applyEstimate should not be called by this

Definition at line 144 of file HandEyeCalibrationVrepPlugin.hpp.

§ getEstimate()

Eigen::Affine3d grl::HandEyeCalibrationVrepPlugin::getEstimate ( )
inline

Definition at line 195 of file HandEyeCalibrationVrepPlugin.hpp.

§ restoreSensorPosition()

void grl::HandEyeCalibrationVrepPlugin::restoreSensorPosition ( )
inline

Correct modified transform for measured optical tracker data.

If real time transform measurements are happening applyEstimate will move the measured object relative to the sensor and this puts the transform measurement back so the object appears in its real position. However, if running in simulation only the sensor will be in the correct position, so you don't want to call this.

Definition at line 206 of file HandEyeCalibrationVrepPlugin.hpp.

Member Data Documentation

§ debug

const bool grl::HandEyeCalibrationVrepPlugin::debug = false
static

Definition at line 50 of file HandEyeCalibrationVrepPlugin.hpp.


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