Skip to content

Commit

Permalink
Add queue_size
Browse files Browse the repository at this point in the history
  • Loading branch information
iory authored and wxmerkt committed Nov 18, 2022
1 parent 0da016c commit e4ad5f9
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 1 deletion.
2 changes: 2 additions & 0 deletions apriltag_ros/launch/continuous_detection.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
<arg name="node_namespace" default="apriltag_ros_continuous_node" />
<arg name="camera_name" default="/camera_rect" />
<arg name="image_topic" default="image_rect" />
<arg name="queue_size" default="1" />

<!-- Set parameters -->
<rosparam command="load" file="$(find apriltag_ros)/config/settings.yaml" ns="$(arg node_namespace)" />
Expand All @@ -14,5 +15,6 @@
<remap from="camera_info" to="$(arg camera_name)/camera_info" />

<param name="publish_tag_detections_image" type="bool" value="true" /> <!-- default: false -->
<param name="queue_size" type="int" value="$(arg queue_size)" />
</node>
</launch>
4 changes: 3 additions & 1 deletion apriltag_ros/src/continuous_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,10 @@ void ContinuousDetector::onInit ()
std::string transport_hint;
pnh.param<std::string>("transport_hint", transport_hint, "raw");

int queue_size;
pnh.param<int>("queue_size", queue_size, 1);
camera_image_subscriber_ =
it_->subscribeCamera("image_rect", 1,
it_->subscribeCamera("image_rect", queue_size,
&ContinuousDetector::imageCallback, this,
image_transport::TransportHints(transport_hint));
tag_detections_publisher_ =
Expand Down

0 comments on commit e4ad5f9

Please sign in to comment.