Skip to content
Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ class ImageTransportDisplay : public rviz_common::_RosTopicDisplay
subscription_ = std::make_shared<image_transport::SubscriberFilter>();
rclcpp::Node::SharedPtr node = rviz_ros_node_.lock()->get_raw_node();
subscription_->subscribe(
node.get(),
*node,
getBaseTopicFromTopic(topic_property_->getTopicStd()),
getTransportFromTopic(topic_property_->getTopicStd()),
qos_profile);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -204,9 +204,9 @@ void DepthCloudDisplay::onInitialize()
auto rviz_ros_node_ = context_->getRosNodeAbstraction().lock();

depthmap_it_ = std::make_unique<image_transport::ImageTransport>(
rviz_ros_node_->get_raw_node());
*rviz_ros_node_->get_raw_node());
rgb_it_ = std::make_unique<image_transport::ImageTransport>(
rviz_ros_node_->get_raw_node());
*rviz_ros_node_->get_raw_node());

// Instantiate PointCloudCommon class for displaying point clouds
pointcloud_common_ = std::make_unique<PointCloudCommon>(this);
Expand Down Expand Up @@ -342,7 +342,7 @@ void DepthCloudDisplay::subscribe()
if (!depthmap_topic.empty() && !depthmap_transport.empty()) {
// subscribe to depth map topic
depthmap_sub_->subscribe(
rviz_ros_node_->get_raw_node().get(),
*rviz_ros_node_->get_raw_node(),
depthmap_topic,
depthmap_transport,
qos_profile_);
Expand Down Expand Up @@ -386,7 +386,7 @@ void DepthCloudDisplay::subscribe()
if (!color_topic.empty() && !color_transport.empty()) {
// subscribe to color image topic
rgb_sub_->subscribe(
rviz_ros_node_->get_raw_node().get(),
*rviz_ros_node_->get_raw_node(),
color_topic, color_transport, qos_profile_);

// connect message filters to synchronizer
Expand Down