From debfb0759ed97666012e8159a13b19e500ae8704 Mon Sep 17 00:00:00 2001 From: matlabbe Date: Thu, 31 Oct 2024 20:37:38 -0700 Subject: [PATCH] Applying https://github.com/introlab/rtabmap_ros/pull/1233 to ros1 --- rtabmap_util/src/nodelets/point_cloud_assembler.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/rtabmap_util/src/nodelets/point_cloud_assembler.cpp b/rtabmap_util/src/nodelets/point_cloud_assembler.cpp index ead6cb0e0..a60779a8e 100644 --- a/rtabmap_util/src/nodelets/point_cloud_assembler.cpp +++ b/rtabmap_util/src/nodelets/point_cloud_assembler.cpp @@ -302,6 +302,7 @@ class PointCloudAssembler : public nodelet::Nodelet void callbackCloud(const sensor_msgs::PointCloud2ConstPtr & cloudMsg) { + callbackCalled_ = true; if(cloudPub_.getNumSubscribers()) { UASSERT_MSG(cloudMsg->data.size() == cloudMsg->row_step*cloudMsg->height,