|
| 1 | +// Copyright 2024 TIER IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include "image_projection_based_fusion/pointpainting_fusion/pointcloud_densification.hpp" |
| 16 | + |
| 17 | +#include <pcl_ros/transforms.hpp> |
| 18 | + |
| 19 | +#include <boost/optional.hpp> |
| 20 | + |
| 21 | +#include <pcl_conversions/pcl_conversions.h> |
| 22 | +#ifdef ROS_DISTRO_GALACTIC |
| 23 | +#include <tf2_eigen/tf2_eigen.h> |
| 24 | +#else |
| 25 | +#include <tf2_eigen/tf2_eigen.hpp> |
| 26 | +#endif |
| 27 | + |
| 28 | +#include <string> |
| 29 | +#include <utility> |
| 30 | + |
| 31 | +namespace |
| 32 | +{ |
| 33 | +boost::optional<geometry_msgs::msg::Transform> getTransform( |
| 34 | + const tf2_ros::Buffer & tf_buffer, const std::string & target_frame_id, |
| 35 | + const std::string & source_frame_id, const rclcpp::Time & time) |
| 36 | +{ |
| 37 | + try { |
| 38 | + geometry_msgs::msg::TransformStamped transform_stamped; |
| 39 | + transform_stamped = tf_buffer.lookupTransform( |
| 40 | + target_frame_id, source_frame_id, time, rclcpp::Duration::from_seconds(0.5)); |
| 41 | + return transform_stamped.transform; |
| 42 | + } catch (tf2::TransformException & ex) { |
| 43 | + RCLCPP_WARN_STREAM(rclcpp::get_logger("lidar_centerpoint"), ex.what()); |
| 44 | + return boost::none; |
| 45 | + } |
| 46 | +} |
| 47 | + |
| 48 | +Eigen::Affine3f transformToEigen(const geometry_msgs::msg::Transform & t) |
| 49 | +{ |
| 50 | + Eigen::Affine3f a; |
| 51 | + a.matrix() = tf2::transformToEigen(t).matrix().cast<float>(); |
| 52 | + return a; |
| 53 | +} |
| 54 | + |
| 55 | +} // namespace |
| 56 | + |
| 57 | +namespace image_projection_based_fusion |
| 58 | +{ |
| 59 | +PointCloudDensification::PointCloudDensification(const centerpoint::DensificationParam & param) |
| 60 | +: param_(param) |
| 61 | +{ |
| 62 | +} |
| 63 | + |
| 64 | +bool PointCloudDensification::enqueuePointCloud( |
| 65 | + const sensor_msgs::msg::PointCloud2 & pointcloud_msg, const tf2_ros::Buffer & tf_buffer) |
| 66 | +{ |
| 67 | + const auto header = pointcloud_msg.header; |
| 68 | + |
| 69 | + if (param_.pointcloud_cache_size() > 1) { |
| 70 | + auto transform_world2current = |
| 71 | + getTransform(tf_buffer, header.frame_id, param_.world_frame_id(), header.stamp); |
| 72 | + if (!transform_world2current) { |
| 73 | + return false; |
| 74 | + } |
| 75 | + auto affine_world2current = transformToEigen(transform_world2current.get()); |
| 76 | + |
| 77 | + enqueue(pointcloud_msg, affine_world2current); |
| 78 | + } else { |
| 79 | + enqueue(pointcloud_msg, Eigen::Affine3f::Identity()); |
| 80 | + } |
| 81 | + |
| 82 | + dequeue(); |
| 83 | + |
| 84 | + return true; |
| 85 | +} |
| 86 | + |
| 87 | +void PointCloudDensification::enqueue( |
| 88 | + const sensor_msgs::msg::PointCloud2 & msg, const Eigen::Affine3f & affine_world2current) |
| 89 | +{ |
| 90 | + affine_world2current_ = affine_world2current; |
| 91 | + current_timestamp_ = rclcpp::Time(msg.header.stamp).seconds(); |
| 92 | + PointCloudWithTransform pointcloud = {msg, affine_world2current.inverse()}; |
| 93 | + pointcloud_cache_.push_front(pointcloud); |
| 94 | +} |
| 95 | + |
| 96 | +void PointCloudDensification::dequeue() |
| 97 | +{ |
| 98 | + if (pointcloud_cache_.size() > param_.pointcloud_cache_size()) { |
| 99 | + pointcloud_cache_.pop_back(); |
| 100 | + } |
| 101 | +} |
| 102 | + |
| 103 | +} // namespace image_projection_based_fusion |
0 commit comments