Skip to content

Commit

Permalink
parameterize marker size
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson committed Feb 7, 2024
1 parent fbf5c36 commit 0d65635
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 1 deletion.
1 change: 1 addition & 0 deletions image_proc/include/image_proc/track_marker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ class TrackMarkerNode : public rclcpp::Node

int queue_size_;
int marker_id_;
double marker_size_;
std::string image_topic_;
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr pub_;

Expand Down
3 changes: 2 additions & 1 deletion image_proc/src/track_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ TrackMarkerNode::TrackMarkerNode(const rclcpp::NodeOptions & options)

// Declare parameters before we setup any publishers or subscribers
marker_id_ = this->declare_parameter("marker_id", 1);
marker_size_ = this->declare_parameter("marker_size", 0.05);

detector_params_ = cv::aruco::DetectorParameters::create();
dictionary_ = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_6X6_250);
Expand Down Expand Up @@ -119,7 +120,7 @@ void TrackMarkerNode::imageCb(

// Estimate pose
std::vector<cv::Vec3d> rvecs, tvecs;
cv::aruco::estimatePoseSingleMarkers(corners, 0.05, intrinsics, dist_coeffs, rvecs, tvecs);
cv::aruco::estimatePoseSingleMarkers(corners, marker_size_, intrinsics, dist_coeffs, rvecs, tvecs);

// Publish pose of marker
geometry_msgs::msg::PoseStamped pose;
Expand Down

0 comments on commit 0d65635

Please sign in to comment.