Classes | Public Member Functions | Public Attributes | Protected Attributes | List of all members
moveit_handeye_calibration::HandEyeTargetBase Class Referenceabstract

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>

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

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< ParametergetParameters ()
 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< Parameterparameters_
 
cv::Vec3d rotation_vect_
 
bool target_params_ready_
 
cv::Vec3d translation_vect_
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ ~HandEyeTargetBase()

virtual moveit_handeye_calibration::HandEyeTargetBase::~HandEyeTargetBase ( )
virtualdefault

◆ HandEyeTargetBase()

moveit_handeye_calibration::HandEyeTargetBase::HandEyeTargetBase ( )
inline

Definition at line 153 of file handeye_target_base.h.

Member Function Documentation

◆ areIntrinsicsReasonable()

virtual bool moveit_handeye_calibration::HandEyeTargetBase::areIntrinsicsReasonable ( )
inlinevirtual

Check that camera intrinsic parameters are reasonable.

Returns
True if intrinsics are reasonable (camera matrix is not all zeros and is not the identity).

Definition at line 304 of file handeye_target_base.h.

◆ convertToQuaternionROSMsg()

geometry_msgs::Quaternion moveit_handeye_calibration::HandEyeTargetBase::convertToQuaternionROSMsg ( const cv::Vec3d &  input_rvect) const
inline

Definition at line 200 of file handeye_target_base.h.

◆ convertToVectorROSMsg()

geometry_msgs::Vector3 moveit_handeye_calibration::HandEyeTargetBase::convertToVectorROSMsg ( const cv::Vec3d &  input_tvect) const
inline

Definition at line 211 of file handeye_target_base.h.

◆ createTargetImage()

virtual bool moveit_handeye_calibration::HandEyeTargetBase::createTargetImage ( cv::Mat &  image) const
pure virtual

Create an target image, so that the target can be viewed and printed.

Parameters
imageUse for storing the created image.
Returns
True if no errors happen, false otherwise.

Implemented in moveit_handeye_calibration::HandEyeArucoTarget, and moveit_handeye_calibration::HandEyeCharucoTarget.

◆ detectTargetPose()

virtual bool moveit_handeye_calibration::HandEyeTargetBase::detectTargetPose ( cv::Mat &  image)
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.

Parameters
imageInput image, assume a grayscale image.
Returns
True if no errors happen, false otherwise.

Implemented in moveit_handeye_calibration::HandEyeArucoTarget, and moveit_handeye_calibration::HandEyeCharucoTarget.

◆ drawAxis()

void moveit_handeye_calibration::HandEyeTargetBase::drawAxis ( cv::InputOutputArray  _image,
cv::InputArray  _cameraMatrix,
cv::InputArray  _distCoeffs,
cv::InputArray  _rvec,
cv::InputArray  _tvec,
float  length 
) const
inline

Definition at line 221 of file handeye_target_base.h.

◆ getParameter() [1/4]

virtual bool moveit_handeye_calibration::HandEyeTargetBase::getParameter ( std::string  name,
double &  value 
) const
inlinevirtual

Get target parameter double value.

Returns
True if successful getting parameter

Definition at line 428 of file handeye_target_base.h.

◆ getParameter() [2/4]

virtual bool moveit_handeye_calibration::HandEyeTargetBase::getParameter ( std::string  name,
float &  value 
) const
inlinevirtual

Get target parameter float value.

Returns
True if successful getting parameter

Definition at line 411 of file handeye_target_base.h.

◆ getParameter() [3/4]

virtual bool moveit_handeye_calibration::HandEyeTargetBase::getParameter ( std::string  name,
int &  value 
) const
inlinevirtual

Get target parameter integer value.

Returns
True if successful getting parameter

Definition at line 394 of file handeye_target_base.h.

◆ getParameter() [4/4]

virtual bool moveit_handeye_calibration::HandEyeTargetBase::getParameter ( std::string  name,
std::string &  value 
) const
inlinevirtual

Get target parameter enum option, as string representation.

Returns
True if successful getting parameter

Definition at line 445 of file handeye_target_base.h.

◆ getParameters()

virtual std::vector<Parameter> moveit_handeye_calibration::HandEyeTargetBase::getParameters ( )
inlinevirtual

Get parameters relevant to this target.

Returns
List of parameter objects

Definition at line 313 of file handeye_target_base.h.

◆ getTransformStamped()

virtual geometry_msgs::TransformStamped moveit_handeye_calibration::HandEyeTargetBase::getTransformStamped ( const std::string &  frame_id) const
inlinevirtual

Get TransformStamped message from the target detection result, use for TF publish.

Parameters
frame_idThe name of the frame this transform is with respect to.
Returns
A TransformStamped message.

Definition at line 186 of file handeye_target_base.h.

◆ initialize()

virtual bool moveit_handeye_calibration::HandEyeTargetBase::initialize ( )
pure virtual

Initialize handeye target. Call after setting the parameters.

Returns
True if initialization was successful, false otherwise.

Implemented in moveit_handeye_calibration::HandEyeArucoTarget, and moveit_handeye_calibration::HandEyeCharucoTarget.

◆ setCameraIntrinsicParams()

virtual bool moveit_handeye_calibration::HandEyeTargetBase::setCameraIntrinsicParams ( const sensor_msgs::CameraInfoConstPtr &  msg)
inlinevirtual

Set camera intrinsic parameters, e.g. camera intrinsic matrix and distortion coefficients.

Parameters
msgInput camera info message.
Returns
True if the input camera info format is correct, false otherwise.

Definition at line 247 of file handeye_target_base.h.

◆ setParameter() [1/4]

virtual bool moveit_handeye_calibration::HandEyeTargetBase::setParameter ( std::string  name,
double  value 
)
inlinevirtual

Set target parameter to double value.

Returns
True if successful setting parameter

Definition at line 356 of file handeye_target_base.h.

◆ setParameter() [2/4]

virtual bool moveit_handeye_calibration::HandEyeTargetBase::setParameter ( std::string  name,
float  value 
)
inlinevirtual

Set target parameter to float value.

Returns
True if successful setting parameter

Definition at line 339 of file handeye_target_base.h.

◆ setParameter() [3/4]

virtual bool moveit_handeye_calibration::HandEyeTargetBase::setParameter ( std::string  name,
int  value 
)
inlinevirtual

Set target parameter to integer value.

Returns
True if successful setting parameter

Definition at line 322 of file handeye_target_base.h.

◆ setParameter() [4/4]

virtual bool moveit_handeye_calibration::HandEyeTargetBase::setParameter ( std::string  name,
std::string  value 
)
inlinevirtual

Set target enum parameter to option specified by string.

Returns
True if successful setting parameter

Definition at line 373 of file handeye_target_base.h.

Member Data Documentation

◆ base_mutex_

std::mutex moveit_handeye_calibration::HandEyeTargetBase::base_mutex_
protected

Definition at line 479 of file handeye_target_base.h.

◆ CAMERA_DISTORTION_MODELS_VECTOR_DIMENSIONS

const std::map<std::string, std::size_t> moveit_handeye_calibration::HandEyeTargetBase::CAMERA_DISTORTION_MODELS_VECTOR_DIMENSIONS
Initial value:
= { { "none", 0 },
{ "plumb_bob", 5 },
{ "rational_polynomial", 8 } }

Definition at line 148 of file handeye_target_base.h.

◆ camera_matrix_

cv::Mat moveit_handeye_calibration::HandEyeTargetBase::camera_matrix_
protected

Definition at line 463 of file handeye_target_base.h.

◆ CAMERA_MATRIX_HEIGHT

const std::size_t moveit_handeye_calibration::HandEyeTargetBase::CAMERA_MATRIX_HEIGHT = 3

Definition at line 147 of file handeye_target_base.h.

◆ CAMERA_MATRIX_VECTOR_DIMENSION

const std::size_t moveit_handeye_calibration::HandEyeTargetBase::CAMERA_MATRIX_VECTOR_DIMENSION = 9

Definition at line 145 of file handeye_target_base.h.

◆ CAMERA_MATRIX_WIDTH

const std::size_t moveit_handeye_calibration::HandEyeTargetBase::CAMERA_MATRIX_WIDTH = 3

Definition at line 146 of file handeye_target_base.h.

◆ distortion_coeffs_

cv::Mat moveit_handeye_calibration::HandEyeTargetBase::distortion_coeffs_
protected

Definition at line 467 of file handeye_target_base.h.

◆ LOGNAME

const std::string moveit_handeye_calibration::HandEyeTargetBase::LOGNAME = "handeye_target_base"

Definition at line 144 of file handeye_target_base.h.

◆ parameters_

std::vector<Parameter> moveit_handeye_calibration::HandEyeTargetBase::parameters_
protected

Definition at line 473 of file handeye_target_base.h.

◆ rotation_vect_

cv::Vec3d moveit_handeye_calibration::HandEyeTargetBase::rotation_vect_
protected

Definition at line 477 of file handeye_target_base.h.

◆ target_params_ready_

bool moveit_handeye_calibration::HandEyeTargetBase::target_params_ready_
protected

Definition at line 470 of file handeye_target_base.h.

◆ translation_vect_

cv::Vec3d moveit_handeye_calibration::HandEyeTargetBase::translation_vect_
protected

Definition at line 476 of file handeye_target_base.h.


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


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