Skip to content

Commit 024ee6c

Browse files
committed
Removed deprecated warnings
Signed-off-by: Alejandro Hernandez Cordero <[email protected]>
1 parent 89521c4 commit 024ee6c

File tree

2 files changed

+43
-5
lines changed

2 files changed

+43
-5
lines changed

src/my_publisher.cpp

Lines changed: 20 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,26 @@ int main(int argc, char ** argv)
5151

5252
auto node = std::make_shared<rclcpp::Node>("point_cloud_publisher");
5353

54-
point_cloud_transport::PointCloudTransport pct(node);
54+
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
55+
rclcpp::node_interfaces::NodeBaseInterface,
56+
rclcpp::node_interfaces::NodeParametersInterface,
57+
rclcpp::node_interfaces::NodeTopicsInterface,
58+
rclcpp::node_interfaces::NodeLoggingInterface
59+
>> node_interfaces = std::make_shared<
60+
rclcpp::node_interfaces::NodeInterfaces<
61+
rclcpp::node_interfaces::NodeBaseInterface,
62+
rclcpp::node_interfaces::NodeParametersInterface,
63+
rclcpp::node_interfaces::NodeTopicsInterface,
64+
rclcpp::node_interfaces::NodeLoggingInterface
65+
>
66+
>(
67+
node->get_node_base_interface(),
68+
node->get_node_parameters_interface(),
69+
node->get_node_topics_interface(),
70+
node->get_node_logging_interface()
71+
);
72+
73+
point_cloud_transport::PointCloudTransport pct(node_interfaces);
5574
point_cloud_transport::Publisher pub = pct.advertise("pct/point_cloud", 100);
5675

5776
const std::string bagged_cloud_topic = "/point_cloud";

src/my_subscriber.cpp

Lines changed: 23 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -36,18 +36,37 @@ int main(int argc, char ** argv)
3636
{
3737
rclcpp::init(argc, argv);
3838
auto node = std::make_shared<rclcpp::Node>("point_cloud_subscriber");
39+
std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<
40+
rclcpp::node_interfaces::NodeBaseInterface,
41+
rclcpp::node_interfaces::NodeParametersInterface,
42+
rclcpp::node_interfaces::NodeTopicsInterface,
43+
rclcpp::node_interfaces::NodeLoggingInterface
44+
>> node_interfaces = std::make_shared<
45+
rclcpp::node_interfaces::NodeInterfaces<
46+
rclcpp::node_interfaces::NodeBaseInterface,
47+
rclcpp::node_interfaces::NodeParametersInterface,
48+
rclcpp::node_interfaces::NodeTopicsInterface,
49+
rclcpp::node_interfaces::NodeLoggingInterface
50+
>
51+
>(
52+
node->get_node_base_interface(),
53+
node->get_node_parameters_interface(),
54+
node->get_node_topics_interface(),
55+
node->get_node_logging_interface()
56+
);
3957

40-
point_cloud_transport::PointCloudTransport pct(node);
58+
point_cloud_transport::PointCloudTransport pct(node_interfaces);
4159
point_cloud_transport::Subscriber pct_sub = pct.subscribe(
4260
"pct/point_cloud", 100,
43-
[node](const sensor_msgs::msg::PointCloud2::ConstSharedPtr & msg)
61+
[node_interfaces](const sensor_msgs::msg::PointCloud2::ConstSharedPtr & msg)
4462
{
4563
RCLCPP_INFO_STREAM(
46-
node->get_logger(),
64+
node_interfaces->get_node_logging_interface()->get_logger(),
4765
"Message received, number of points is: " << msg->width * msg->height);
4866
}, {});
4967

50-
RCLCPP_INFO_STREAM(node->get_logger(), "Waiting for point_cloud message...");
68+
RCLCPP_INFO_STREAM(node_interfaces->get_node_logging_interface()->get_logger(),
69+
"Waiting for point_cloud message...");
5170

5271
rclcpp::spin(node);
5372

0 commit comments

Comments
 (0)