Skip to content

Commit

Permalink
image_view: consistent image_transport (#876)
Browse files Browse the repository at this point in the history
All of these nodes already have the proper remapping support - but
image_transport parameter support was scattered
  • Loading branch information
mikeferguson authored Jan 19, 2024
1 parent 1fbe467 commit a2fb282
Show file tree
Hide file tree
Showing 5 changed files with 26 additions and 12 deletions.
6 changes: 4 additions & 2 deletions image_view/src/extract_images_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,13 +75,15 @@ ExtractImagesNode::ExtractImagesNode(const rclcpp::NodeOptions & options)
auto node_base = this->get_node_base_interface();
std::string topic = node_base->resolve_topic_or_service_name("image", false);

this->declare_parameter<std::string>("transport", std::string("raw"));
// TransportHints does not actually declare the parameter
this->declare_parameter<std::string>("image_transport", "raw");
image_transport::TransportHints hints(this);
std::string transport = this->get_parameter("transport").as_string();

sub_ = image_transport::create_subscription(
this, topic, std::bind(
&ExtractImagesNode::image_cb, this, std::placeholders::_1),
transport);
hints.getTransport());

auto topics = this->get_topic_names_and_types();

Expand Down
8 changes: 6 additions & 2 deletions image_view/src/image_saver_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,10 @@ namespace image_view
ImageSaverNode::ImageSaverNode(const rclcpp::NodeOptions & options)
: rclcpp::Node("image_saver_node", options)
{
// TransportHints does not actually declare the parameter
this->declare_parameter<std::string>("image_transport", "raw");
image_transport::TransportHints hints(this);

// For compressed topics to remap appropriately, we need to pass a
// fully expanded and remapped topic name to image_transport
auto node_base = this->get_node_base_interface();
Expand All @@ -80,13 +84,13 @@ ImageSaverNode::ImageSaverNode(const rclcpp::NodeOptions & options)
cam_sub_ = image_transport::create_camera_subscription(
this, topic, std::bind(
&ImageSaverNode::callbackWithCameraInfo, this, std::placeholders::_1, std::placeholders::_2),
"raw");
hints.getTransport());

// Useful when CameraInfo is not being published
image_sub_ = image_transport::create_subscription(
this, topic, std::bind(
&ImageSaverNode::callbackWithoutCameraInfo, this, std::placeholders::_1),
"raw");
hints.getTransport());

std::string format_string;
format_string = this->declare_parameter("filename_format", std::string("left%04i.%s"));
Expand Down
7 changes: 4 additions & 3 deletions image_view/src/image_view_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,15 +104,16 @@ cv_bridge::CvImageConstPtr ThreadSafeImage::pop()
ImageViewNode::ImageViewNode(const rclcpp::NodeOptions & options)
: rclcpp::Node("image_view_node", options)
{
auto transport = this->declare_parameter("image_transport", "raw");
RCLCPP_INFO(this->get_logger(), "Using transport \"%s\"", transport.c_str());
// TransportHints does not actually declare the parameter
this->declare_parameter<std::string>("image_transport", "raw");
image_transport::TransportHints hints(this);
RCLCPP_INFO(this->get_logger(), "Using transport \"%s\"", hints.getTransport().c_str());

// For compressed topics to remap appropriately, we need to pass a
// fully expanded and remapped topic name to image_transport
auto node_base = this->get_node_base_interface();
std::string topic = node_base->resolve_topic_or_service_name("image", false);

image_transport::TransportHints hints(this, transport);
pub_ = this->create_publisher<sensor_msgs::msg::Image>("output", 1);
sub_ = image_transport::create_subscription(
this, topic, std::bind(
Expand Down
9 changes: 5 additions & 4 deletions image_view/src/stereo_view_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,8 +97,9 @@ StereoViewNode::StereoViewNode(const rclcpp::NodeOptions & options)
std::string format_string = this->get_parameter("filename_format").as_string();
filename_format_.parse(format_string);

this->declare_parameter<std::string>("transport", std::string("raw"));
std::string transport = this->get_parameter("transport").as_string();
// TransportHints does not actually declare the parameter
this->declare_parameter<std::string>("image_transport", std::string("raw"));
image_transport::TransportHints hints(this);

// Do GUI window setup
int flags = autosize ? (cv::WINDOW_AUTOSIZE | cv::WINDOW_KEEPRATIO | cv::WINDOW_GUI_EXPANDED) : 0;
Expand Down Expand Up @@ -126,8 +127,8 @@ StereoViewNode::StereoViewNode(const rclcpp::NodeOptions & options)
stereo_ns + "/disparity", this->get_name(), this->get_namespace());

// Subscribe to three input topics.
left_sub_.subscribe(this, left_topic, transport);
right_sub_.subscribe(this, right_topic, transport);
left_sub_.subscribe(this, left_topic, hints.getTransport());
right_sub_.subscribe(this, right_topic, hints.getTransport());
disparity_sub_.subscribe(this, disparity_topic);

RCLCPP_INFO(
Expand Down
8 changes: 7 additions & 1 deletion image_view/src/video_recorder_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,13 +66,19 @@ VideoRecorderNode::VideoRecorderNode(const rclcpp::NodeOptions & options)
rclcpp::shutdown();
}

// TransportHints does not actually declare the parameter
this->declare_parameter<std::string>("image_transport", "raw");
image_transport::TransportHints hints(this);

// For compressed topics to remap appropriately, we need to pass a
// fully expanded and remapped topic name to image_transport
auto node_base = this->get_node_base_interface();
std::string topic = node_base->resolve_topic_or_service_name("image", false);

sub_image = image_transport::create_subscription(
this, topic, std::bind(&VideoRecorderNode::callback, this, std::placeholders::_1), "raw");
this, topic, std::bind(
&VideoRecorderNode::callback, this,
std::placeholders::_1), hints.getTransport());

RCLCPP_INFO(this->get_logger(), "Waiting for topic %s...", topic.c_str());
}
Expand Down

0 comments on commit a2fb282

Please sign in to comment.