#include <PivotCalibrationVrepPlugin.hpp>
Public Types | |
enum | ParamIndex { ToolTipToModifyName, ToolTipToMeasureName, ToolBaseToModifyName, ToolBaseToMeasureName } |
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 | estimatePivotOffset () |
run solver to estimate the unknown transform and set the simulation to the estimated value More... | |
Eigen::Affine3d | getEstimate () |
PivotCalibrationVrepPlugin (Params params=defaultParams()) | |
void | restoreSensorPosition () |
Correct modified transform for measured optical tracker data. More... | |
void | setAlgorithm (std::string algorithm_) |
Static Public Member Functions | |
static const Params | defaultParams () |
Static Public Attributes | |
static const bool | debug = false |
Creates a complete vrep plugin object usage:
Definition at line 45 of file PivotCalibrationVrepPlugin.hpp.
typedef std::tuple< std::string, std::string, std::string, std::string > grl::PivotCalibrationVrepPlugin::Params |
Definition at line 62 of file PivotCalibrationVrepPlugin.hpp.
Definition at line 50 of file PivotCalibrationVrepPlugin.hpp.
|
inline |
Definition at line 75 of file PivotCalibrationVrepPlugin.hpp.
|
inline |
Definition at line 106 of file PivotCalibrationVrepPlugin.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 185 of file PivotCalibrationVrepPlugin.hpp.
|
inline |
construct() function completes initialization of the plugin
Definition at line 88 of file PivotCalibrationVrepPlugin.hpp.
|
inlinestatic |
Definition at line 65 of file PivotCalibrationVrepPlugin.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
TODO(ahundt) use Ransac pivot calibration wrapper because there will likely be noise
TODO(ahundt) Allow selection of "TWO_STEP_PROECDURE" and "COMBINATORIAL_APPROACH" from V-REP LUA API
Definition at line 140 of file PivotCalibrationVrepPlugin.hpp.
|
inline |
Definition at line 191 of file PivotCalibrationVrepPlugin.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 202 of file PivotCalibrationVrepPlugin.hpp.
|
inline |
Possible algorithms are: TWO_STEP_PROCEDURE, //!< First, estimate the pivot point in global coordinates. Second, estimate the sought translation by computing the difference vector between the pivot point and the center of the sensor system; then take the mean.
This algorithm is advantageous in the case of zero-mean noise. COMBINATORICAL_APPROACH //!< Setup n equations that yield the pivot point from a single measurement using the sought (but unknown) translation. Eliminate the pivot point in the system of equations and finally solve for the sought translation.
This algorithm is advantageous in the case of non-zero-mean noise (e.g. a systematic error).
If the algorithm string doesn't match an existing algorithm, this API will assume TWO_STEP_PROCEDURE.
Definition at line 100 of file PivotCalibrationVrepPlugin.hpp.
|
static |
Definition at line 48 of file PivotCalibrationVrepPlugin.hpp.