Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Allows user to use CompressedImage #129

Open
wants to merge 2 commits into
base: humble-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions aruco_ros/launch/single.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ def launch_setup(context, *args, **kwargs):
'camera_frame': 'stereo_gazebo_' + eye + '_camera_optical_frame',
'marker_frame': LaunchConfiguration('marker_frame'),
'corner_refinement': LaunchConfiguration('corner_refinement'),
'image_transport': LaunchConfiguration('image_transport'),
}

aruco_single = Node(
Expand Down Expand Up @@ -65,6 +66,12 @@ def generate_launch_description():
choices=['NONE', 'HARRIS', 'LINES', 'SUBPIX'],
)

image_transport_arg = DeclareLaunchArgument(
'image_transport', default_value='raw',
description='Image Transport. ',
choices=['raw', 'compressed'],
)

# Create the launch description and populate
ld = LaunchDescription()

Expand All @@ -74,6 +81,7 @@ def generate_launch_description():
ld.add_action(marker_frame_arg)
ld.add_action(reference_frame)
ld.add_action(corner_refinement_arg)
ld.add_action(image_transport_arg)

ld.add_action(OpaqueFunction(function=launch_setup))

Expand Down
6 changes: 4 additions & 2 deletions aruco_ros/src/simple_single.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,7 @@ class ArucoSimple : public rclcpp::Node
int marker_id;

std::unique_ptr<image_transport::ImageTransport> it_;
image_transport::TransportHints hints;
image_transport::Subscriber image_sub;

std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
Expand All @@ -88,7 +89,7 @@ class ArucoSimple : public rclcpp::Node

public:
ArucoSimple()
: Node("aruco_single"), cam_info_received(false)
: Node("aruco_single"), cam_info_received(false), hints(this)
{
}

Expand Down Expand Up @@ -133,6 +134,7 @@ class ArucoSimple : public rclcpp::Node
this->declare_parameter<bool>("image_is_rectified", true);
this->declare_parameter<float>("min_marker_size", 0.02);
this->declare_parameter<std::string>("detection_mode", "");
this->declare_parameter<std::string>("image_transport", "raw");

float min_marker_size; // percentage of image area
this->get_parameter_or<float>("min_marker_size", min_marker_size, 0.02);
Expand All @@ -152,7 +154,7 @@ class ArucoSimple : public rclcpp::Node
this->get_logger(), "Marker size min: " << min_marker_size << " of image area");
RCLCPP_INFO_STREAM(this->get_logger(), "Detection mode: " << detection_mode);

image_sub = it_->subscribe("/image", 1, &ArucoSimple::image_callback, this);
image_sub = it_->subscribe("/image", 1, &ArucoSimple::image_callback, this, &hints);
cam_info_sub = this->create_subscription<sensor_msgs::msg::CameraInfo>(
"/camera_info", 1, std::bind(
&ArucoSimple::cam_info_callback, this,
Expand Down