Skip to content

Commit 3df8aa6

Browse files
authored
Removed deprecation warning in tf2 (ros-visualization#1585)
Signed-off-by: Alejandro Hernandez Cordero <ahcorde@gmail.com>
1 parent 46045f9 commit 3df8aa6

File tree

9 files changed

+9
-9
lines changed

9 files changed

+9
-9
lines changed

rviz_common/include/rviz_common/adapter_filter_display.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -137,7 +137,7 @@ class RosAdapterFilterDisplay : public _RosTopicDisplay
137137
*context_->getFrameManager()->getTransformer(),
138138
fixed_frame_.toStdString(),
139139
static_cast<uint32_t>(message_queue_property_->getInt()),
140-
node);
140+
*node);
141141
tf_filter_->connectInput(*subscription_);
142142
tf_filter_->registerCallback(
143143
std::bind(

rviz_common/include/rviz_common/message_filter_display.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -134,7 +134,7 @@ class MessageFilterDisplay : public _RosTopicDisplay
134134
*context_->getFrameManager()->getTransformer(),
135135
fixed_frame_.toStdString(),
136136
static_cast<uint32_t>(message_queue_property_->getInt()),
137-
node);
137+
*node);
138138
tf_filter_->connectInput(*subscription_);
139139
tf_filter_->registerCallback(
140140
std::bind(

rviz_default_plugins/include/rviz_default_plugins/displays/pointcloud/point_cloud_transport_display.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ class PointCloud2TransportDisplay : public rviz_common::MessageFilterDisplay<Mes
8686
rviz_common::transformation::FrameTransformer>>(
8787
*this->context_->getFrameManager()->getTransformer(),
8888
this->fixed_frame_.toStdString(),
89-
static_cast<uint32_t>(this->message_queue_property_->getInt()), node);
89+
static_cast<uint32_t>(this->message_queue_property_->getInt()), *node);
9090
this->tf_filter_->connectInput(*subscriber_filter_);
9191
this->tf_filter_->registerCallback(
9292
std::bind(&PointCloud2TransportDisplay<MessageType>::messageTaken, this,

rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -325,7 +325,7 @@ void CameraDisplay::subscribe()
325325
tf2_ros::MessageFilter<sensor_msgs::msg::Image,
326326
rviz_common::transformation::FrameTransformer>>(
327327
*context_->getFrameManager()->getTransformer(),
328-
fixed_frame_.toStdString(), 10, rviz_ros_node_.lock()->get_raw_node());
328+
fixed_frame_.toStdString(), 10, *rviz_ros_node_.lock()->get_raw_node());
329329

330330
tf_filter_->connectInput(*subscription_);
331331
tf_filter_->registerCallback(

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -353,7 +353,7 @@ void DepthCloudDisplay::subscribe()
353353
*context_->getFrameManager()->getTransformer(),
354354
fixed_frame_.toStdString(),
355355
queue_size_,
356-
rviz_ros_node_->get_raw_node());
356+
*rviz_ros_node_->get_raw_node());
357357

358358
depthmap_tf_filter_->connectInput(*depthmap_sub_);
359359

rviz_default_plugins/src/rviz_default_plugins/transformation/tf_wrapper.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -139,7 +139,7 @@ void TFWrapper::initialize(
139139
*buffer_, true);
140140
} else {
141141
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
142-
*buffer_, rviz_ros_node.lock()->get_raw_node(), false);
142+
*buffer_, *rviz_ros_node.lock()->get_raw_node(), false);
143143
}
144144
}
145145

rviz_default_plugins/test/rviz_default_plugins/publishers/odometry_publisher.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,7 @@ class OdometryPublisher : public rclcpp::Node
6464
// constructor once available.
6565
void initialize()
6666
{
67-
broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(shared_from_this());
67+
broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(*shared_from_this());
6868
}
6969

7070
private:

rviz_visual_testing_framework/include/rviz_visual_testing_framework/transform_publisher.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -98,7 +98,7 @@ class TransformPublisher
9898
void publishOnFrame()
9999
{
100100
auto transformer_publisher_node = std::make_shared<rclcpp::Node>("static_transform_publisher");
101-
tf2_ros::StaticTransformBroadcaster broadcaster(transformer_publisher_node);
101+
tf2_ros::StaticTransformBroadcaster broadcaster(*transformer_publisher_node);
102102

103103
rclcpp::WallRate loop_rate(0.2);
104104
rclcpp::executors::SingleThreadedExecutor executor;

rviz_visual_testing_framework/include/rviz_visual_testing_framework/visual_test_publisher.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -85,7 +85,7 @@ class VisualTestPublisher
8585
void publishOnFrame(std::vector<PublisherWithFrame> publishers)
8686
{
8787
auto transformer_publisher_node = std::make_shared<rclcpp::Node>("static_transform_publisher");
88-
tf2_ros::StaticTransformBroadcaster broadcaster(transformer_publisher_node);
88+
tf2_ros::StaticTransformBroadcaster broadcaster(*transformer_publisher_node);
8989

9090
rclcpp::executors::SingleThreadedExecutor executor;
9191
executor.add_node(transformer_publisher_node);

0 commit comments

Comments
 (0)