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

#include <handeye_target_charuco.h>

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

Public Member Functions

virtual bool createTargetImage (cv::Mat &image) const override
 Create an target image, so that the target can be viewed and printed. More...
 
virtual bool detectTargetPose (cv::Mat &image) override
 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...
 
 HandEyeCharucoTarget ()
 
virtual bool initialize () override
 Initialize handeye target. Call after setting the parameters. More...
 
 ~HandEyeCharucoTarget ()=default
 
- Public Member Functions inherited from moveit_handeye_calibration::HandEyeTargetBase
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
 
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 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
 

Protected Member Functions

virtual bool setTargetDimension (double board_size_meters, double marker_size_meters)
 
virtual bool setTargetIntrinsicParams (int markers_x, int markers_y, int marker_size_pixels, int square_size_pixels, int border_size_bits, int margin_size_pixels, const std::string &dictionary_id)
 

Private Attributes

double board_size_meters_
 
int border_size_bits_
 
std::mutex charuco_mutex_
 
cv::aruco::PREDEFINED_DICTIONARY_NAME dictionary_id_
 
int margin_size_pixels_
 
std::map< std::string, cv::aruco::PREDEFINED_DICTIONARY_NAME > marker_dictionaries_
 
double marker_size_meters_
 
int marker_size_pixels_
 
int square_size_pixels_
 
int squares_x_
 
int squares_y_
 

Additional Inherited Members

- Public Attributes inherited from moveit_handeye_calibration::HandEyeTargetBase
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 inherited from moveit_handeye_calibration::HandEyeTargetBase
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

Definition at line 79 of file handeye_target_charuco.h.

Constructor & Destructor Documentation

◆ HandEyeCharucoTarget()

moveit_handeye_calibration::HandEyeCharucoTarget::HandEyeCharucoTarget ( )

Definition at line 84 of file handeye_target_charuco.cpp.

◆ ~HandEyeCharucoTarget()

moveit_handeye_calibration::HandEyeCharucoTarget::~HandEyeCharucoTarget ( )
default

Member Function Documentation

◆ createTargetImage()

bool moveit_handeye_calibration::HandEyeCharucoTarget::createTargetImage ( cv::Mat &  image) const
overridevirtual

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.

Implements moveit_handeye_calibration::HandEyeTargetBase.

Definition at line 186 of file handeye_target_charuco.cpp.

◆ detectTargetPose()

bool moveit_handeye_calibration::HandEyeCharucoTarget::detectTargetPose ( cv::Mat &  image)
overridevirtual

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.

Implements moveit_handeye_calibration::HandEyeTargetBase.

Definition at line 213 of file handeye_target_charuco.cpp.

◆ initialize()

bool moveit_handeye_calibration::HandEyeCharucoTarget::initialize ( )
overridevirtual

Initialize handeye target. Call after setting the parameters.

Returns
True if initialization was successful, false otherwise.

Implements moveit_handeye_calibration::HandEyeTargetBase.

Definition at line 102 of file handeye_target_charuco.cpp.

◆ setTargetDimension()

bool moveit_handeye_calibration::HandEyeCharucoTarget::setTargetDimension ( double  board_size_meters,
double  marker_size_meters 
)
protectedvirtual

Definition at line 163 of file handeye_target_charuco.cpp.

◆ setTargetIntrinsicParams()

bool moveit_handeye_calibration::HandEyeCharucoTarget::setTargetIntrinsicParams ( int  markers_x,
int  markers_y,
int  marker_size_pixels,
int  square_size_pixels,
int  border_size_bits,
int  margin_size_pixels,
const std::string &  dictionary_id 
)
protectedvirtual

Definition at line 129 of file handeye_target_charuco.cpp.

Member Data Documentation

◆ board_size_meters_

double moveit_handeye_calibration::HandEyeCharucoTarget::board_size_meters_
private

Definition at line 143 of file handeye_target_charuco.h.

◆ border_size_bits_

int moveit_handeye_calibration::HandEyeCharucoTarget::border_size_bits_
private

Definition at line 138 of file handeye_target_charuco.h.

◆ charuco_mutex_

std::mutex moveit_handeye_calibration::HandEyeCharucoTarget::charuco_mutex_
private

Definition at line 146 of file handeye_target_charuco.h.

◆ dictionary_id_

cv::aruco::PREDEFINED_DICTIONARY_NAME moveit_handeye_calibration::HandEyeCharucoTarget::dictionary_id_
private

Definition at line 140 of file handeye_target_charuco.h.

◆ margin_size_pixels_

int moveit_handeye_calibration::HandEyeCharucoTarget::margin_size_pixels_
private

Definition at line 139 of file handeye_target_charuco.h.

◆ marker_dictionaries_

std::map<std::string, cv::aruco::PREDEFINED_DICTIONARY_NAME> moveit_handeye_calibration::HandEyeCharucoTarget::marker_dictionaries_
private

Definition at line 131 of file handeye_target_charuco.h.

◆ marker_size_meters_

double moveit_handeye_calibration::HandEyeCharucoTarget::marker_size_meters_
private

Definition at line 144 of file handeye_target_charuco.h.

◆ marker_size_pixels_

int moveit_handeye_calibration::HandEyeCharucoTarget::marker_size_pixels_
private

Definition at line 136 of file handeye_target_charuco.h.

◆ square_size_pixels_

int moveit_handeye_calibration::HandEyeCharucoTarget::square_size_pixels_
private

Definition at line 137 of file handeye_target_charuco.h.

◆ squares_x_

int moveit_handeye_calibration::HandEyeCharucoTarget::squares_x_
private

Definition at line 134 of file handeye_target_charuco.h.

◆ squares_y_

int moveit_handeye_calibration::HandEyeCharucoTarget::squares_y_
private

Definition at line 135 of file handeye_target_charuco.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