Skip to content

Commit

Permalink
use TransportHints
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson committed Jan 19, 2024
1 parent ab8409f commit 6755ce5
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 6 deletions.
1 change: 0 additions & 1 deletion image_rotate/include/image_rotate/image_rotate_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,6 @@ struct ImageRotateConfig
bool use_camera_info;
double max_angular_rate;
double output_image_size;
std::string transport;
};

class ImageRotateNode : public rclcpp::Node
Expand Down
12 changes: 7 additions & 5 deletions image_rotate/src/image_rotate_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,8 +128,8 @@ ImageRotateNode::ImageRotateNode(const rclcpp::NodeOptions & options)
config_.max_angular_rate = this->declare_parameter("max_angular_rate", 10.0);
config_.output_image_size = this->declare_parameter("output_image_size", 2.0);

// Allow overriding the SUBSCRIBER transport
config_.transport = this->declare_parameter("image_transport", "raw");
// TransportHints does not actually declare the parameter
this->declare_parameter<std::string>("image_transport", "raw");

onInit();
}
Expand Down Expand Up @@ -300,6 +300,7 @@ void ImageRotateNode::onInit()
// fully expanded and remapped topic name to image_transport
auto node_base = this->get_node_base_interface();
std::string topic_name = node_base->resolve_topic_or_service_name("image", false);
RCLCPP_INFO(get_logger(), "Subscribing to %s topic.", topic_name.c_str());

// Check that remapping appears to be correct
auto topics = this->get_topic_names_and_types();
Expand All @@ -311,7 +312,8 @@ void ImageRotateNode::onInit()
topic_name.c_str());
}

RCLCPP_INFO(get_logger(), "Subscribing to %s topic.", topic_name.c_str());
// This will check image_transport parameter to get proper transport
image_transport::TransportHints transport_hint(this, "raw");

if (config_.use_camera_info && config_.input_frame_id.empty()) {
auto custom_qos = rmw_qos_profile_system_default;
Expand All @@ -322,7 +324,7 @@ void ImageRotateNode::onInit()
std::bind(
&ImageRotateNode::imageCallbackWithInfo, this,
std::placeholders::_1, std::placeholders::_2),
config_.transport,
transport_hint.getTransport(),
custom_qos);
} else {
auto custom_qos = rmw_qos_profile_system_default;
Expand All @@ -331,7 +333,7 @@ void ImageRotateNode::onInit()
this,
topic_name,
std::bind(&ImageRotateNode::imageCallback, this, std::placeholders::_1),
config_.transport,
transport_hint.getTransport(),
custom_qos);
}
}
Expand Down

0 comments on commit 6755ce5

Please sign in to comment.