Skip to content

Commit

Permalink
same treatment, more nodes
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson committed Jan 18, 2024
1 parent 90823d6 commit 257d411
Show file tree
Hide file tree
Showing 5 changed files with 25 additions and 13 deletions.
10 changes: 7 additions & 3 deletions image_view/src/disparity_view_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,10 +65,14 @@ namespace image_view
DisparityViewNode::DisparityViewNode(const rclcpp::NodeOptions & options)
: rclcpp::Node("disparity_view_node", options)
{
std::string topic =
rclcpp::expand_topic_or_service_name("image", this->get_name(), this->get_namespace());
// 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);

if (topic == "image") {
auto topics = this->get_topic_names_and_types();

if (topics.find(topic) == topics.end()) {
RCLCPP_WARN(
this->get_logger(), "Topic 'image' has not been remapped! Typical command-line usage:\n"
"\t$ ros2 run image_view disparity_view --ros-args -r image:=<disparity image topic>");
Expand Down
8 changes: 5 additions & 3 deletions image_view/src/extract_images_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,10 @@ ExtractImagesNode::ExtractImagesNode(const rclcpp::NodeOptions & options)
: rclcpp::Node("extract_images_node", options),
filename_format_(""), count_(0), _time(this->now())
{
auto topic = rclcpp::expand_topic_or_service_name(
"image", this->get_name(), this->get_namespace());
// 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);

this->declare_parameter<std::string>("transport", std::string("raw"));
std::string transport = this->get_parameter("transport").as_string();
Expand All @@ -83,7 +85,7 @@ ExtractImagesNode::ExtractImagesNode(const rclcpp::NodeOptions & options)

auto topics = this->get_topic_names_and_types();

if (topics.find(topic) != topics.end()) {
if (topics.find(topic) == topics.end()) {
RCLCPP_WARN(
this->get_logger(), "extract_images: image has not been remapped! "
"Typical command-line usage:\n\t$ ros2 run image_view extract_images "
Expand Down
6 changes: 4 additions & 2 deletions image_view/src/image_saver_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,10 @@ namespace image_view
ImageSaverNode::ImageSaverNode(const rclcpp::NodeOptions & options)
: rclcpp::Node("image_saver_node", options)
{
auto topic = rclcpp::expand_topic_or_service_name(
"image", this->get_name(), this->get_namespace());
// 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);

// Useful when CameraInfo is being published
cam_sub_ = image_transport::create_camera_subscription(
Expand Down
7 changes: 4 additions & 3 deletions image_view/src/stereo_view_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,9 +109,10 @@ StereoViewNode::StereoViewNode(const rclcpp::NodeOptions & options)
cv::setMouseCallback("right", &StereoViewNode::mouseCb, this);
cv::setMouseCallback("disparity", &StereoViewNode::mouseCb, this);

// Resolve topic names
std::string stereo_ns = rclcpp::expand_topic_or_service_name(
"stereo", this->get_name(), this->get_namespace());
// 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 stereo_ns = node_base->resolve_topic_or_service_name("stereo", false);

std::string left_topic = rclcpp::expand_topic_or_service_name(
stereo_ns + "/left" + rclcpp::expand_topic_or_service_name(
Expand Down
7 changes: 5 additions & 2 deletions image_view/src/video_recorder_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,11 @@ VideoRecorderNode::VideoRecorderNode(const rclcpp::NodeOptions & options)
rclcpp::shutdown();
}

auto topic = rclcpp::expand_topic_or_service_name(
"image", this->get_name(), this->get_namespace());
// 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");

Expand Down

0 comments on commit 257d411

Please sign in to comment.