#include <handeye_solver_default.h>
Definition at line 59 of file handeye_solver_default.h.
◆ HandEyeSolverDefault()
| moveit_handeye_calibration::HandEyeSolverDefault::HandEyeSolverDefault |
( |
| ) |
|
|
default |
◆ ~HandEyeSolverDefault()
| moveit_handeye_calibration::HandEyeSolverDefault::~HandEyeSolverDefault |
( |
| ) |
|
|
default |
◆ getCameraRobotPose()
| const Eigen::Isometry3d & moveit_handeye_calibration::HandEyeSolverDefault::getCameraRobotPose |
( |
| ) |
const |
|
overridevirtual |
◆ getSolverNames()
| const std::vector< std::string > & moveit_handeye_calibration::HandEyeSolverDefault::getSolverNames |
( |
| ) |
const |
|
overridevirtual |
◆ initialize()
| void moveit_handeye_calibration::HandEyeSolverDefault::initialize |
( |
| ) |
|
|
overridevirtual |
◆ solve()
| bool moveit_handeye_calibration::HandEyeSolverDefault::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 = "TsaiLenz1989", |
|
|
std::string * |
error_message = nullptr |
|
) |
| |
|
overridevirtual |
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.
Implements moveit_handeye_calibration::HandEyeSolverBase.
Definition at line 96 of file handeye_solver_default.cpp.
◆ toCArray()
| bool moveit_handeye_calibration::HandEyeSolverDefault::toCArray |
( |
const Eigen::Isometry3d & |
pose, |
|
|
double(*) |
c_arr[TRANSFORM_MATRIX_DIMENSION] |
|
) |
| const |
|
private |
Convert a Eigen::Isometry3d pose to a 4x4 C array.
- Parameters
-
| pose | A Eigen::Isometry3d pose. |
| c_arr | Pointer to a C array of 4 elements. |
Definition at line 450 of file handeye_solver_default.cpp.
◆ camera_robot_pose_
| Eigen::Isometry3d moveit_handeye_calibration::HandEyeSolverDefault::camera_robot_pose_ |
|
private |
◆ solver_names_
| std::vector<std::string> moveit_handeye_calibration::HandEyeSolverDefault::solver_names_ |
|
private |
The documentation for this class was generated from the following files: