#include <HandEyeCalibrationVrepPlugin.hpp>
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 |
Creates a complete vrep plugin object usage:
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.
typedef std::tuple< std::string, std::string, std::string, std::string > grl::HandEyeCalibrationVrepPlugin::Params |
Definition at line 65 of file HandEyeCalibrationVrepPlugin.hpp.
Definition at line 52 of file HandEyeCalibrationVrepPlugin.hpp.
|
inline |
Definition at line 78 of file HandEyeCalibrationVrepPlugin.hpp.
|
inline |
Definition at line 99 of file HandEyeCalibrationVrepPlugin.hpp.
|
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.
|
inline |
construct() function completes initialization of the plugin
Definition at line 91 of file HandEyeCalibrationVrepPlugin.hpp.
|
inlinestatic |
Definition at line 68 of file HandEyeCalibrationVrepPlugin.hpp.
|
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
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.
|
inline |
Definition at line 195 of file HandEyeCalibrationVrepPlugin.hpp.
|
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.
|
static |
Definition at line 50 of file HandEyeCalibrationVrepPlugin.hpp.