Skip to content

Commit

Permalink
Merge branch 'ros2' of github.com:introlab/rtabmap_ros into updating_…
Browse files Browse the repository at this point in the history
…examples_and_readme
  • Loading branch information
matlabbe committed Nov 25, 2024
2 parents a73a792 + e9aa8ed commit c133f35
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion rtabmap_util/src/nodelets/point_cloud_assembler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down

0 comments on commit c133f35

Please # to comment.