diff --git a/demo_cpp/11_pointcloud_data.cpp b/demo_cpp/11_pointcloud_data.cpp index 2cebe91..84326f8 100644 --- a/demo_cpp/11_pointcloud_data.cpp +++ b/demo_cpp/11_pointcloud_data.cpp @@ -28,7 +28,10 @@ int main(int argc, char **argv) node = std::make_shared("pointcloud_data_node"); auto pc_sub = node->create_subscription( - "/kinect2/sd/points", 1, PointcloudCallback); + "/kinect2/sd/points", + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)).best_effort(), + PointcloudCallback + ); rclcpp::spin(node); diff --git a/demo_cpp/11_pointcloud_objects.cpp b/demo_cpp/11_pointcloud_objects.cpp index 7799a3f..f8d5f8d 100644 --- a/demo_cpp/11_pointcloud_objects.cpp +++ b/demo_cpp/11_pointcloud_objects.cpp @@ -113,7 +113,10 @@ int main(int argc, char **argv) tf_listener_ = std::make_shared(*tf_buffer_); auto pc_sub = node->create_subscription( - "/kinect2/sd/points", 1, PointcloudCallback); + "/kinect2/sd/points", + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)).best_effort(), + PointcloudCallback + ); rclcpp::spin(node); diff --git a/demo_cpp/11_pointcloud_objects_class.cpp b/demo_cpp/11_pointcloud_objects_class.cpp index 808042a..4e3785c 100644 --- a/demo_cpp/11_pointcloud_objects_class.cpp +++ b/demo_cpp/11_pointcloud_objects_class.cpp @@ -20,7 +20,9 @@ public: tf_listener_ = std::make_shared(*tf_buffer_); pc_sub_ = this->create_subscription( - "/kinect2/sd/points", 10, std::bind(&PointcloudObjects::pointcloudCallback, this, std::placeholders::_1)); + "/kinect2/sd/points", + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)).best_effort(), + std::bind(&PointcloudObjects::pointcloudCallback, this, std::placeholders::_1)); } private: