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,