File tree Expand file tree Collapse file tree 2 files changed +9
-3
lines changed Expand file tree Collapse file tree 2 files changed +9
-3
lines changed Original file line number Diff line number Diff line change @@ -52,6 +52,9 @@ int main(int argc, char ** argv)
5252
5353 auto node = std::make_shared< rclcpp::Node > ("point_cloud_publisher");
5454
55+ rclcpp::executors::SingleThreadedExecutor executor;
56+ executor.add_node(node);
57+
5558 point_cloud_transport::PointCloudTransport pct(node);
5659 point_cloud_transport::Publisher pub = pct.advertise("pct/point_cloud", 100);
5760
@@ -83,7 +86,7 @@ int main(int argc, char ** argv)
8386 cloud_serialization.deserialize_message(&extracted_serialized_msg, &cloud_msg);
8487 // publish the message
8588 pub.publish(cloud_msg);
86- rclcpp:: spin_some(node );
89+ executor. spin_some();
8790 rclcpp::sleep_for(std::chrono::milliseconds(100));
8891 }
8992 }
@@ -121,7 +124,7 @@ Publishes sensor_msgs::PointCloud2 message from the specified rosbag:
121124 // publish the message
122125 pub.publish(cloud_msg);
123126 // spin the node...
124- rclcpp:: spin_some (node );
127+ executor. spin_some();
125128 // repeat...
126129```
127130
Original file line number Diff line number Diff line change @@ -51,6 +51,9 @@ int main(int argc, char ** argv)
5151
5252 auto node = std::make_shared<rclcpp::Node>(" point_cloud_publisher" );
5353
54+ rclcpp::executors::SingleThreadedExecutor executor;
55+ executor.add_node (node);
56+
5457 point_cloud_transport::PointCloudTransport pct (*node);
5558 point_cloud_transport::Publisher pub = pct.advertise (" pct/point_cloud" , 100 );
5659
@@ -93,7 +96,7 @@ int main(int argc, char ** argv)
9396 cloud_serialization.deserialize_message (&extracted_serialized_msg, &cloud_msg);
9497 // publish the message
9598 pub.publish (cloud_msg);
96- rclcpp:: spin_some (node );
99+ executor. spin_some ();
97100 rclcpp::sleep_for (std::chrono::milliseconds (100 ));
98101 }
99102 }
You can’t perform that action at this time.
0 commit comments