diff --git a/src/my_publisher.cpp b/src/my_publisher.cpp index 732808d..e0dc04c 100644 --- a/src/my_publisher.cpp +++ b/src/my_publisher.cpp @@ -51,7 +51,7 @@ int main(int argc, char ** argv) auto node = std::make_shared("point_cloud_publisher"); - point_cloud_transport::PointCloudTransport pct(node); + point_cloud_transport::PointCloudTransport pct(*node); point_cloud_transport::Publisher pub = pct.advertise("pct/point_cloud", 100); const std::string bagged_cloud_topic = "/point_cloud"; diff --git a/src/my_subscriber.cpp b/src/my_subscriber.cpp index 468d140..2fa1687 100644 --- a/src/my_subscriber.cpp +++ b/src/my_subscriber.cpp @@ -37,7 +37,7 @@ int main(int argc, char ** argv) rclcpp::init(argc, argv); auto node = std::make_shared("point_cloud_subscriber"); - point_cloud_transport::PointCloudTransport pct(node); + point_cloud_transport::PointCloudTransport pct(*node); point_cloud_transport::Subscriber pct_sub = pct.subscribe( "pct/point_cloud", 100, [node](const sensor_msgs::msg::PointCloud2::ConstSharedPtr & msg)