#include <handeye_target_aruco.h>

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... | |
| HandEyeArucoTarget () | |
| virtual bool | initialize () override |
| Initialize handeye target. Call after setting the parameters. More... | |
| ~HandEyeArucoTarget ()=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< 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 | 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 marker_measured_size, double marker_measured_separation) |
| virtual bool | setTargetIntrinsicParams (int markers_x, int markers_y, int marker_size, int separation, int border_bits, const std::string &dictionary_id) |
Private Attributes | |
| std::mutex | aruco_mutex_ |
| int | border_bits_ |
| cv::aruco::PREDEFINED_DICTIONARY_NAME | dictionary_id_ |
| std::map< std::string, cv::aruco::PREDEFINED_DICTIONARY_NAME > | marker_dictionaries_ |
| double | marker_separation_real_ |
| int | marker_size_ |
| double | marker_size_real_ |
| int | markers_x_ |
| int | markers_y_ |
| int | separation_ |
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< Parameter > | parameters_ |
| cv::Vec3d | rotation_vect_ |
| bool | target_params_ready_ |
| cv::Vec3d | translation_vect_ |
Definition at line 79 of file handeye_target_aruco.h.
| moveit_handeye_calibration::HandEyeArucoTarget::HandEyeArucoTarget | ( | ) |
Definition at line 84 of file handeye_target_aruco.cpp.
|
default |
|
overridevirtual |
Create an target image, so that the target can be viewed and printed.
| image | Use for storing the created image. |
Implements moveit_handeye_calibration::HandEyeTargetBase.
Definition at line 176 of file handeye_target_aruco.cpp.
|
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.
| image | Input image, assume a grayscale image. |
Implements moveit_handeye_calibration::HandEyeTargetBase.
Definition at line 201 of file handeye_target_aruco.cpp.
|
overridevirtual |
Initialize handeye target. Call after setting the parameters.
Implements moveit_handeye_calibration::HandEyeTargetBase.
Definition at line 101 of file handeye_target_aruco.cpp.
|
protectedvirtual |
Definition at line 156 of file handeye_target_aruco.cpp.
|
protectedvirtual |
Definition at line 126 of file handeye_target_aruco.cpp.
|
private |
Definition at line 145 of file handeye_target_aruco.h.
|
private |
Definition at line 138 of file handeye_target_aruco.h.
|
private |
Definition at line 139 of file handeye_target_aruco.h.
|
private |
Definition at line 131 of file handeye_target_aruco.h.
|
private |
Definition at line 143 of file handeye_target_aruco.h.
|
private |
Definition at line 136 of file handeye_target_aruco.h.
|
private |
Definition at line 142 of file handeye_target_aruco.h.
|
private |
Definition at line 134 of file handeye_target_aruco.h.
|
private |
Definition at line 135 of file handeye_target_aruco.h.
|
private |
Definition at line 137 of file handeye_target_aruco.h.