Provides an interface for handeye calibration target detectors. A target used for handeye calibration is usually a 2D board that consists of an array of markers. The markers can be circles, rectangles or their combinations. More...
#include <handeye_target_base.h>

Classes | |
| class | Parameter |
Public Member Functions | |
| virtual bool | areIntrinsicsReasonable () |
| Check that camera intrinsic parameters are reasonable. More... | |
| geometry_msgs::Quaternion | convertToQuaternionROSMsg (const cv::Vec3d &input_rvect) const |
| geometry_msgs::Vector3 | convertToVectorROSMsg (const cv::Vec3d &input_tvect) const |
| virtual bool | createTargetImage (cv::Mat &image) const =0 |
| Create an target image, so that the target can be viewed and printed. More... | |
| virtual bool | detectTargetPose (cv::Mat &image)=0 |
| Given an image containing a target captured from a camera view point, get the target pose with respect to the camera optical frame. Target parameters and camera intrinsic parameters should be correctly set before calling this function. More... | |
| void | drawAxis (cv::InputOutputArray _image, cv::InputArray _cameraMatrix, cv::InputArray _distCoeffs, cv::InputArray _rvec, cv::InputArray _tvec, float length) const |
| virtual bool | getParameter (std::string name, double &value) const |
| Get target parameter double value. More... | |
| virtual bool | getParameter (std::string name, float &value) const |
| Get target parameter float value. More... | |
| virtual bool | getParameter (std::string name, int &value) const |
| Get target parameter integer value. More... | |
| virtual bool | getParameter (std::string name, std::string &value) const |
| Get target parameter enum option, as string representation. More... | |
| virtual std::vector< Parameter > | getParameters () |
| Get parameters relevant to this target. More... | |
| virtual geometry_msgs::TransformStamped | getTransformStamped (const std::string &frame_id) const |
Get TransformStamped message from the target detection result, use for TF publish. More... | |
| HandEyeTargetBase () | |
| virtual bool | initialize ()=0 |
| Initialize handeye target. Call after setting the parameters. More... | |
| virtual bool | setCameraIntrinsicParams (const sensor_msgs::CameraInfoConstPtr &msg) |
| Set camera intrinsic parameters, e.g. camera intrinsic matrix and distortion coefficients. More... | |
| virtual bool | setParameter (std::string name, double value) |
| Set target parameter to double value. More... | |
| virtual bool | setParameter (std::string name, float value) |
| Set target parameter to float value. More... | |
| virtual bool | setParameter (std::string name, int value) |
| Set target parameter to integer value. More... | |
| virtual bool | setParameter (std::string name, std::string value) |
| Set target enum parameter to option specified by string. More... | |
| virtual | ~HandEyeTargetBase ()=default |
Public Attributes | |
| const std::map< std::string, std::size_t > | CAMERA_DISTORTION_MODELS_VECTOR_DIMENSIONS |
| const std::size_t | CAMERA_MATRIX_HEIGHT = 3 |
| const std::size_t | CAMERA_MATRIX_VECTOR_DIMENSION = 9 |
| const std::size_t | CAMERA_MATRIX_WIDTH = 3 |
| const std::string | LOGNAME = "handeye_target_base" |
Protected Attributes | |
| std::mutex | base_mutex_ |
| cv::Mat | camera_matrix_ |
| cv::Mat | distortion_coeffs_ |
| std::vector< Parameter > | parameters_ |
| cv::Vec3d | rotation_vect_ |
| bool | target_params_ready_ |
| cv::Vec3d | translation_vect_ |
Provides an interface for handeye calibration target detectors. A target used for handeye calibration is usually a 2D board that consists of an array of markers. The markers can be circles, rectangles or their combinations.
Definition at line 90 of file handeye_target_base.h.
|
virtualdefault |
|
inline |
Definition at line 153 of file handeye_target_base.h.
|
inlinevirtual |
Check that camera intrinsic parameters are reasonable.
Definition at line 304 of file handeye_target_base.h.
|
inline |
Definition at line 200 of file handeye_target_base.h.
|
inline |
Definition at line 211 of file handeye_target_base.h.
|
pure virtual |
Create an target image, so that the target can be viewed and printed.
| image | Use for storing the created image. |
Implemented in moveit_handeye_calibration::HandEyeArucoTarget, and moveit_handeye_calibration::HandEyeCharucoTarget.
|
pure virtual |
Given an image containing a target captured from a camera view point, get the target pose with respect to the camera optical frame. Target parameters and camera intrinsic parameters should be correctly set before calling this function.
| image | Input image, assume a grayscale image. |
Implemented in moveit_handeye_calibration::HandEyeArucoTarget, and moveit_handeye_calibration::HandEyeCharucoTarget.
|
inline |
Definition at line 221 of file handeye_target_base.h.
|
inlinevirtual |
Get target parameter double value.
Definition at line 428 of file handeye_target_base.h.
|
inlinevirtual |
Get target parameter float value.
Definition at line 411 of file handeye_target_base.h.
|
inlinevirtual |
Get target parameter integer value.
Definition at line 394 of file handeye_target_base.h.
|
inlinevirtual |
Get target parameter enum option, as string representation.
Definition at line 445 of file handeye_target_base.h.
|
inlinevirtual |
Get parameters relevant to this target.
Definition at line 313 of file handeye_target_base.h.
|
inlinevirtual |
Get TransformStamped message from the target detection result, use for TF publish.
| frame_id | The name of the frame this transform is with respect to. |
TransformStamped message. Definition at line 186 of file handeye_target_base.h.
|
pure virtual |
Initialize handeye target. Call after setting the parameters.
Implemented in moveit_handeye_calibration::HandEyeArucoTarget, and moveit_handeye_calibration::HandEyeCharucoTarget.
|
inlinevirtual |
Set camera intrinsic parameters, e.g. camera intrinsic matrix and distortion coefficients.
| msg | Input camera info message. |
Definition at line 247 of file handeye_target_base.h.
|
inlinevirtual |
Set target parameter to double value.
Definition at line 356 of file handeye_target_base.h.
|
inlinevirtual |
Set target parameter to float value.
Definition at line 339 of file handeye_target_base.h.
|
inlinevirtual |
Set target parameter to integer value.
Definition at line 322 of file handeye_target_base.h.
|
inlinevirtual |
Set target enum parameter to option specified by string.
Definition at line 373 of file handeye_target_base.h.
|
protected |
Definition at line 479 of file handeye_target_base.h.
| const std::map<std::string, std::size_t> moveit_handeye_calibration::HandEyeTargetBase::CAMERA_DISTORTION_MODELS_VECTOR_DIMENSIONS |
Definition at line 148 of file handeye_target_base.h.
|
protected |
Definition at line 463 of file handeye_target_base.h.
| const std::size_t moveit_handeye_calibration::HandEyeTargetBase::CAMERA_MATRIX_HEIGHT = 3 |
Definition at line 147 of file handeye_target_base.h.
| const std::size_t moveit_handeye_calibration::HandEyeTargetBase::CAMERA_MATRIX_VECTOR_DIMENSION = 9 |
Definition at line 145 of file handeye_target_base.h.
| const std::size_t moveit_handeye_calibration::HandEyeTargetBase::CAMERA_MATRIX_WIDTH = 3 |
Definition at line 146 of file handeye_target_base.h.
|
protected |
Definition at line 467 of file handeye_target_base.h.
| const std::string moveit_handeye_calibration::HandEyeTargetBase::LOGNAME = "handeye_target_base" |
Definition at line 144 of file handeye_target_base.h.
|
protected |
Definition at line 473 of file handeye_target_base.h.
|
protected |
Definition at line 477 of file handeye_target_base.h.
|
protected |
Definition at line 470 of file handeye_target_base.h.
|
protected |
Definition at line 476 of file handeye_target_base.h.