Public Member Functions | Private Member Functions | Private Attributes | List of all members
moveit_handeye_calibration::HandEyeSolverDefault Class Reference

#include <handeye_solver_default.h>

Inheritance diagram for moveit_handeye_calibration::HandEyeSolverDefault:
Inheritance graph
[legend]

Public Member Functions

virtual const Eigen::Isometry3d & getCameraRobotPose () const override
 Get the result of the calibration, i.e. the camera pose with respect to the robot. More...
 
virtual const std::vector< std::string > & getSolverNames () const override
 Get the names of available algorithms that can be used from the plugin. More...
 
 HandEyeSolverDefault ()=default
 
virtual void initialize () override
 
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="TsaiLenz1989", std::string *error_message=nullptr) override
 Calculate camera-robot transform from the input pose samples. More...
 
 ~HandEyeSolverDefault ()=default
 
- Public Member Functions inherited from moveit_handeye_calibration::HandEyeSolverBase
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...
 
 HandEyeSolverBase ()=default
 
virtual ~HandEyeSolverBase ()=default
 

Private Member Functions

bool toCArray (const Eigen::Isometry3d &pose, double(*c_arr)[TRANSFORM_MATRIX_DIMENSION]) const
 Convert a Eigen::Isometry3d pose to a 4x4 C array. More...
 

Private Attributes

Eigen::Isometry3d camera_robot_pose_
 
std::vector< std::string > solver_names_
 

Detailed Description

Definition at line 59 of file handeye_solver_default.h.

Constructor & Destructor Documentation

◆ HandEyeSolverDefault()

moveit_handeye_calibration::HandEyeSolverDefault::HandEyeSolverDefault ( )
default

◆ ~HandEyeSolverDefault()

moveit_handeye_calibration::HandEyeSolverDefault::~HandEyeSolverDefault ( )
default

Member Function Documentation

◆ getCameraRobotPose()

const Eigen::Isometry3d & moveit_handeye_calibration::HandEyeSolverDefault::getCameraRobotPose ( ) const
overridevirtual

Get the result of the calibration, i.e. the camera pose with respect to the robot.

Returns
A 4X4 transform indicating the pose.

Implements moveit_handeye_calibration::HandEyeSolverBase.

Definition at line 91 of file handeye_solver_default.cpp.

◆ getSolverNames()

const std::vector< std::string > & moveit_handeye_calibration::HandEyeSolverDefault::getSolverNames ( ) const
overridevirtual

Get the names of available algorithms that can be used from the plugin.

Returns
A vector storing the names.

Implements moveit_handeye_calibration::HandEyeSolverBase.

Definition at line 86 of file handeye_solver_default.cpp.

◆ 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_worldEnd-effector pose (4X4 transform) with respect to the world (or robot base).
object_wrt_sensorObject (calibration board) pose (4X4 transform) with respect to the camera.
setupCamera mount type, {EYE_TO_HAND, EYE_IN_HAND}.
solver_nameThe algorithm used in the calculation.
[out]error_messageDescription 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
poseA Eigen::Isometry3d pose.
c_arrPointer to a C array of 4 elements.

Definition at line 450 of file handeye_solver_default.cpp.

Member Data Documentation

◆ camera_robot_pose_

Eigen::Isometry3d moveit_handeye_calibration::HandEyeSolverDefault::camera_robot_pose_
private

Definition at line 84 of file handeye_solver_default.h.

◆ solver_names_

std::vector<std::string> moveit_handeye_calibration::HandEyeSolverDefault::solver_names_
private

Definition at line 83 of file handeye_solver_default.h.


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


moveit_calibration_plugins
Author(s): Yu Yan
autogenerated on Fri Oct 18 2024 02:14:08