|
void | fillCorners (aruco_pose::Marker &marker, const vector< cv::Point2f > &corners) const |
|
void | fillPose (geometry_msgs::Pose &pose, const cv::Vec3d &rvec, const cv::Vec3d &tvec) const |
|
void | fillTranslation (geometry_msgs::Vector3 &translation, const cv::Vec3d &tvec) const |
|
std::string | getChildFrameId (int id) const |
|
double | getMarkerLength (int id) |
|
void | imageCallback (const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cinfo) |
|
void | mapMarkersCallback (const aruco_pose::MarkerArray &msg) |
|
void | paramCallback (aruco_pose::DetectorConfig &config, uint32_t level) |
|
void | pushVisMarkers (const std::string &frame_id, const ros::Time &stamp, const geometry_msgs::Pose &pose, double length, int id, int index) |
|
void | readLengthOverride (ros::NodeHandle &nh) |
|
Definition at line 59 of file aruco_detect.cpp.
◆ fillCorners()
void ArucoDetect::fillCorners |
( |
aruco_pose::Marker & |
marker, |
|
|
const vector< cv::Point2f > & |
corners |
|
) |
| const |
|
inlineprivate |
◆ fillPose()
void ArucoDetect::fillPose |
( |
geometry_msgs::Pose & |
pose, |
|
|
const cv::Vec3d & |
rvec, |
|
|
const cv::Vec3d & |
tvec |
|
) |
| const |
|
inlineprivate |
◆ fillTranslation()
void ArucoDetect::fillTranslation |
( |
geometry_msgs::Vector3 & |
translation, |
|
|
const cv::Vec3d & |
tvec |
|
) |
| const |
|
inlineprivate |
◆ getChildFrameId()
std::string ArucoDetect::getChildFrameId |
( |
int |
id | ) |
const |
|
inlineprivate |
◆ getMarkerLength()
double ArucoDetect::getMarkerLength |
( |
int |
id | ) |
|
|
inlineprivate |
◆ imageCallback()
void ArucoDetect::imageCallback |
( |
const sensor_msgs::ImageConstPtr & |
msg, |
|
|
const sensor_msgs::CameraInfoConstPtr & |
cinfo |
|
) |
| |
|
inlineprivate |
◆ mapMarkersCallback()
void ArucoDetect::mapMarkersCallback |
( |
const aruco_pose::MarkerArray & |
msg | ) |
|
|
inlineprivate |
◆ onInit()
virtual void ArucoDetect::onInit |
( |
| ) |
|
|
inlinevirtual |
◆ paramCallback()
void ArucoDetect::paramCallback |
( |
aruco_pose::DetectorConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
inlineprivate |
◆ pushVisMarkers()
void ArucoDetect::pushVisMarkers |
( |
const std::string & |
frame_id, |
|
|
const ros::Time & |
stamp, |
|
|
const geometry_msgs::Pose & |
pose, |
|
|
double |
length, |
|
|
int |
id, |
|
|
int |
index |
|
) |
| |
|
inlineprivate |
◆ readLengthOverride()
◆ array_
aruco_pose::MarkerArray ArucoDetect::array_ |
|
private |
◆ auto_flip_
bool ArucoDetect::auto_flip_ |
|
private |
◆ br_
◆ camera_matrix_
Mat ArucoDetect::camera_matrix_ |
|
private |
◆ debug_pub_
◆ dictionary_
◆ dist_coeffs_
Mat ArucoDetect::dist_coeffs_ |
|
private |
◆ dyn_srv_
std::shared_ptr<dynamic_reconfigure::Server<aruco_pose::DetectorConfig> > ArucoDetect::dyn_srv_ |
|
private |
◆ enabled_
bool ArucoDetect::enabled_ = true |
|
private |
◆ estimate_poses_
bool ArucoDetect::estimate_poses_ |
|
private |
◆ frame_id_prefix_
std::string ArucoDetect::frame_id_prefix_ |
|
private |
◆ img_sub_
◆ known_tilt_
std::string ArucoDetect::known_tilt_ |
|
private |
◆ length_
double ArucoDetect::length_ |
|
private |
◆ length_override_
std::unordered_map<int, double> ArucoDetect::length_override_ |
|
private |
◆ map_markers_ids_
std::unordered_set<int> ArucoDetect::map_markers_ids_ |
|
private |
◆ map_markers_sub_
◆ markers_pub_
◆ parameters_
◆ send_tf_
bool ArucoDetect::send_tf_ |
|
private |
◆ tf_buffer_
◆ tf_listener_
◆ vis_array_
visualization_msgs::MarkerArray ArucoDetect::vis_array_ |
|
private |
◆ vis_markers_pub_
The documentation for this class was generated from the following file: