#include <handeye_solver_base.h>
|
| virtual const Eigen::Isometry3d & | getCameraRobotPose () const =0 |
| | Get the result of the calibration, i.e. the camera pose with respect to the robot. More...
|
| |
| std::pair< double, double > | getReprojectionError (const std::vector< Eigen::Isometry3d > &effector_wrt_world, const std::vector< Eigen::Isometry3d > &object_wrt_sensor, const Eigen::Isometry3d &X, SensorMountType setup=EYE_TO_HAND) |
| | Get the reprojection error for the given samples. More...
|
| |
| virtual const std::vector< std::string > & | getSolverNames () const =0 |
| | Get the names of available algorithms that can be used from the plugin. More...
|
| |
| | HandEyeSolverBase ()=default |
| |
| virtual void | initialize ()=0 |
| |
| virtual bool | solve (const std::vector< Eigen::Isometry3d > &effector_wrt_world, const std::vector< Eigen::Isometry3d > &object_wrt_sensor, SensorMountType setup=EYE_TO_HAND, const std::string &solver_name="", std::string *error_message=nullptr)=0 |
| | Calculate camera-robot transform from the input pose samples. More...
|
| |
| virtual | ~HandEyeSolverBase ()=default |
| |
Definition at line 82 of file handeye_solver_base.h.
◆ HandEyeSolverBase()
| moveit_handeye_calibration::HandEyeSolverBase::HandEyeSolverBase |
( |
| ) |
|
|
default |
◆ ~HandEyeSolverBase()
| virtual moveit_handeye_calibration::HandEyeSolverBase::~HandEyeSolverBase |
( |
| ) |
|
|
virtualdefault |
◆ getCameraRobotPose()
| virtual const Eigen::Isometry3d& moveit_handeye_calibration::HandEyeSolverBase::getCameraRobotPose |
( |
| ) |
const |
|
pure virtual |
◆ getReprojectionError()
| std::pair<double, double> moveit_handeye_calibration::HandEyeSolverBase::getReprojectionError |
( |
const std::vector< Eigen::Isometry3d > & |
effector_wrt_world, |
|
|
const std::vector< Eigen::Isometry3d > & |
object_wrt_sensor, |
|
|
const Eigen::Isometry3d & |
X, |
|
|
SensorMountType |
setup = EYE_TO_HAND |
|
) |
| |
|
inline |
Get the reprojection error for the given samples.
- Parameters
-
| effector_wrt_world | End-effector pose (4X4 transform) with respect to the world (or robot base). |
| object_wrt_sensor | Object (calibration board) pose (4X4 transform) with respect to the camera. |
| X | The calibration, as a 4X4 transform. |
| setup | Camera mount type, {EYE_TO_HAND, EYE_IN_HAND}. |
- Returns
- Pair of translation and rotation reprojection error in meters and radians, or NaNs on error.
Definition at line 129 of file handeye_solver_base.h.
◆ getSolverNames()
| virtual const std::vector<std::string>& moveit_handeye_calibration::HandEyeSolverBase::getSolverNames |
( |
| ) |
const |
|
pure virtual |
◆ initialize()
| virtual void moveit_handeye_calibration::HandEyeSolverBase::initialize |
( |
| ) |
|
|
pure virtual |
◆ solve()
| virtual bool moveit_handeye_calibration::HandEyeSolverBase::solve |
( |
const std::vector< Eigen::Isometry3d > & |
effector_wrt_world, |
|
|
const std::vector< Eigen::Isometry3d > & |
object_wrt_sensor, |
|
|
SensorMountType |
setup = EYE_TO_HAND, |
|
|
const std::string & |
solver_name = "", |
|
|
std::string * |
error_message = nullptr |
|
) |
| |
|
pure virtual |
Calculate camera-robot transform from the input pose samples.
- Parameters
-
| effector_wrt_world | End-effector pose (4X4 transform) with respect to the world (or robot base). |
| object_wrt_sensor | Object (calibration board) pose (4X4 transform) with respect to the camera. |
| setup | Camera mount type, {EYE_TO_HAND, EYE_IN_HAND}. |
| solver_name | The algorithm used in the calculation. |
| [out] | error_message | Description of error, if solver fails |
- Returns
- If the calculation succeeds, return true. Otherwise, return false.
Implemented in moveit_handeye_calibration::HandEyeSolverDefault.
The documentation for this class was generated from the following file: