Skip to content

Commit 7248938

Browse files
authored
Support image transport lifecycle (#1472)
Signed-off-by: Alejandro Hernandez Cordero <[email protected]>
1 parent 55bb914 commit 7248938

File tree

2 files changed

+5
-5
lines changed

2 files changed

+5
-5
lines changed

rviz_default_plugins/include/rviz_default_plugins/displays/image/image_transport_display.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -115,7 +115,7 @@ class ImageTransportDisplay : public rviz_common::_RosTopicDisplay
115115
subscription_ = std::make_shared<image_transport::SubscriberFilter>();
116116
rclcpp::Node::SharedPtr node = rviz_ros_node_.lock()->get_raw_node();
117117
subscription_->subscribe(
118-
node.get(),
118+
*node,
119119
getBaseTopicFromTopic(topic_property_->getTopicStd()),
120120
getTransportFromTopic(topic_property_->getTopicStd()),
121121
qos_profile);

rviz_default_plugins/src/rviz_default_plugins/displays/depth_cloud/depth_cloud_display.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -204,9 +204,9 @@ void DepthCloudDisplay::onInitialize()
204204
auto rviz_ros_node_ = context_->getRosNodeAbstraction().lock();
205205

206206
depthmap_it_ = std::make_unique<image_transport::ImageTransport>(
207-
rviz_ros_node_->get_raw_node());
207+
*rviz_ros_node_->get_raw_node());
208208
rgb_it_ = std::make_unique<image_transport::ImageTransport>(
209-
rviz_ros_node_->get_raw_node());
209+
*rviz_ros_node_->get_raw_node());
210210

211211
// Instantiate PointCloudCommon class for displaying point clouds
212212
pointcloud_common_ = std::make_unique<PointCloudCommon>(this);
@@ -342,7 +342,7 @@ void DepthCloudDisplay::subscribe()
342342
if (!depthmap_topic.empty() && !depthmap_transport.empty()) {
343343
// subscribe to depth map topic
344344
depthmap_sub_->subscribe(
345-
rviz_ros_node_->get_raw_node().get(),
345+
*rviz_ros_node_->get_raw_node(),
346346
depthmap_topic,
347347
depthmap_transport,
348348
qos_profile_);
@@ -386,7 +386,7 @@ void DepthCloudDisplay::subscribe()
386386
if (!color_topic.empty() && !color_transport.empty()) {
387387
// subscribe to color image topic
388388
rgb_sub_->subscribe(
389-
rviz_ros_node_->get_raw_node().get(),
389+
*rviz_ros_node_->get_raw_node(),
390390
color_topic, color_transport, qos_profile_);
391391

392392
// connect message filters to synchronizer

0 commit comments

Comments
 (0)