From e9aa8ed082a2669f52186d2802645bb1237634f8 Mon Sep 17 00:00:00 2001 From: chcaya <55998117+chcaya@users.noreply.github.com> Date: Thu, 31 Oct 2024 23:35:56 -0400 Subject: [PATCH] Fixed callbackCloud warning (#1233) * Fixed callbackCloud warning * reverted warning order --------- Co-authored-by: chcaya Co-authored-by: matlabbe --- rtabmap_util/src/nodelets/point_cloud_assembler.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/rtabmap_util/src/nodelets/point_cloud_assembler.cpp b/rtabmap_util/src/nodelets/point_cloud_assembler.cpp index 2264af399..fa1b95d8d 100644 --- a/rtabmap_util/src/nodelets/point_cloud_assembler.cpp +++ b/rtabmap_util/src/nodelets/point_cloud_assembler.cpp @@ -286,13 +286,14 @@ void PointCloudAssembler::callbackCloudOdomInfo( } else { - RCLCPP_WARN(this->get_logger(), "Reseting point cloud assembler as null odometry has been received."); + RCLCPP_WARN(this->get_logger(), "Resetting point cloud assembler as null odometry has been received."); clouds_.clear(); } } void PointCloudAssembler::callbackCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr cloudMsg) { + callbackCalled_ = true; if(cloudPub_->get_subscription_count()) { UASSERT_MSG(cloudMsg->data.size() == cloudMsg->row_step*cloudMsg->height,