diff --git a/autoware_utils/README.md b/autoware_utils/README.md index 253aa6e..a5597e9 100644 --- a/autoware_utils/README.md +++ b/autoware_utils/README.md @@ -47,7 +47,6 @@ The ROS module provides utilities for working with ROS messages and nodes: - **`debug_publisher.hpp`**: A helper class for publishing debug messages with timestamps. - **`diagnostics_interface.hpp`**: An interface for publishing diagnostic messages. - **`logger_level_configure.hpp`**: Utility for configuring logger levels dynamically. -- **`managed_transform_buffer.hpp`**: A managed buffer for handling static and dynamic transforms. - **`marker_helper.hpp`**: Helper functions for creating and manipulating visualization markers. - **`msg_covariance.hpp`**: Indices for accessing covariance matrices in ROS messages. - **`msg_operation.hpp`**: Overloaded operators for quaternion messages. @@ -56,12 +55,10 @@ The ROS module provides utilities for working with ROS messages and nodes: - **`processing_time_publisher.hpp`**: Publishes processing times as diagnostic messages. - **`published_time_publisher.hpp`**: Tracks and publishes the time when messages are published. - **`self_pose_listener.hpp`**: Listens to the self-pose of the vehicle. -- **`transform_listener.hpp`**: Manages transformation listeners. - **`update_param.hpp`**: Updates parameters from remote nodes. - **`uuid_helper.hpp`**: Utilities for generating and managing UUIDs. - **`wait_for_param.hpp`**: Waits for parameters from remote nodes. - **`debug_traits.hpp`**: Traits for identifying debug message types. -- **`pcl_conversion.hpp`**: Efficient conversion and transformation of PointCloud2 messages to PCL point clouds. #### System Module @@ -72,10 +69,6 @@ The system module provides low-level utilities for performance monitoring and er - **`stop_watch.hpp`**: Measures elapsed time for profiling. - **`time_keeper.hpp`**: Tracks and reports the processing time of various functions. -#### Transform Module - -Efficient methods for transforming and manipulating point clouds. - ## Usage ### Including Headers @@ -140,36 +133,6 @@ int main() { ### Detailed Usage Examples -#### Transform Point Clouds with ManagedTransformBuffer - -```cpp -#include "autoware_utils/ros/managed_transform_buffer.hpp" -#include "sensor_msgs/msg/point_cloud2.hpp" -#include - -int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); - auto node = rclcpp::Node::make_shared("transform_node"); - - // Initialize ManagedTransformBuffer - autoware_utils::ManagedTransformBuffer transform_buffer(node, false); - - // Load point cloud data - sensor_msgs::msg::PointCloud2 cloud_in; // Assume this is populated with data - sensor_msgs::msg::PointCloud2 cloud_out; - - // Transform point cloud from "base_link" to "map" frame - if (transform_buffer.transform_pointcloud("map", cloud_in, cloud_out)) { - RCLCPP_INFO(node->get_logger(), "Point cloud transformed successfully."); - } else { - RCLCPP_ERROR(node->get_logger(), "Failed to transform point cloud."); - } - - rclcpp::shutdown(); - return 0; -} -``` - #### Update Parameters Dynamically with update_param.hpp ```cpp @@ -250,36 +213,6 @@ int main(int argc, char * argv[]) { } ``` -#### Efficient Point Cloud Conversion with pcl_conversion.hpp - -```cpp -#include "autoware_utils/ros/pcl_conversion.hpp" -#include "sensor_msgs/msg/point_cloud2.hpp" -#include -#include -#include -#include - -int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); - auto node = rclcpp::Node::make_shared("pcl_conversion_node"); - - // Load point cloud data - sensor_msgs::msg::PointCloud2 cloud_in; // Assume this is populated with data - pcl::PointCloud pcl_cloud; - - // Define transformation matrix - Eigen::Matrix4f transform = Eigen::Matrix4f::Identity(); - // Populate transform matrix with actual values - - // Convert and transform point cloud - autoware_utils::transform_point_cloud_from_ros_msg(cloud_in, pcl_cloud, transform); - - rclcpp::shutdown(); - return 0; -} -``` - #### Handling Debug Message Types with debug_traits.hpp ```cpp diff --git a/autoware_utils/include/autoware_utils/ros/managed_transform_buffer.hpp b/autoware_utils/include/autoware_utils/ros/managed_transform_buffer.hpp index a14dbf8..12547a5 100644 --- a/autoware_utils/include/autoware_utils/ros/managed_transform_buffer.hpp +++ b/autoware_utils/include/autoware_utils/ros/managed_transform_buffer.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 TIER IV, Inc. +// Copyright 2025 The Autoware Contributors // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -15,213 +15,12 @@ #ifndef AUTOWARE_UTILS__ROS__MANAGED_TRANSFORM_BUFFER_HPP_ #define AUTOWARE_UTILS__ROS__MANAGED_TRANSFORM_BUFFER_HPP_ -#include "autoware_utils/ros/transform_listener.hpp" - -#include -#include -#include - -#include - -#include - -#include -#include -#include -#include -#include -#include -#include - -namespace std -{ -template <> -struct hash> -{ - size_t operator()(const std::pair & p) const - { - size_t h1 = std::hash{}(p.first); - size_t h2 = std::hash{}(p.second); - return h1 ^ (h2 << 1u); - } -}; -} // namespace std +#include namespace autoware_utils { -using std::chrono_literals::operator""ms; -using Key = std::pair; -struct PairEqual -{ - bool operator()(const Key & p1, const Key & p2) const - { - return p1.first == p2.first && p1.second == p2.second; - } -}; -using TFMap = std::unordered_map, PairEqual>; -constexpr std::array warn_frames = {"map", "odom", "world"}; - -class ManagedTransformBuffer -{ -public: - explicit ManagedTransformBuffer(rclcpp::Node * node, const bool & has_static_tf_only) - : node_(node) - { - if (has_static_tf_only) { - get_transform_ = [this]( - const std::string & target_frame, const std::string & source_frame, - Eigen::Matrix4f & eigen_transform) { - return get_static_transform(target_frame, source_frame, eigen_transform); - }; - } else { - tf_listener_ = std::make_unique(node); - get_transform_ = [this]( - const std::string & target_frame, const std::string & source_frame, - Eigen::Matrix4f & eigen_transform) { - return get_dynamic_transform(target_frame, source_frame, eigen_transform); - }; - } - } - - bool get_transform( - const std::string & target_frame, const std::string & source_frame, - Eigen::Matrix4f & eigen_transform) - { - return get_transform_(target_frame, source_frame, eigen_transform); - } - - /** - * Transforms a point cloud from one frame to another. - * - * @param target_frame The target frame to transform the point cloud to. - * @param cloud_in The input point cloud to be transformed. - * @param cloud_out The transformed point cloud. - * @return True if the transformation is successful, false otherwise. - */ - bool transform_pointcloud( - const std::string & target_frame, const sensor_msgs::msg::PointCloud2 & cloud_in, - sensor_msgs::msg::PointCloud2 & cloud_out) - { - if ( - pcl::getFieldIndex(cloud_in, "x") == -1 || pcl::getFieldIndex(cloud_in, "y") == -1 || - pcl::getFieldIndex(cloud_in, "z") == -1) { - RCLCPP_ERROR(node_->get_logger(), "Input pointcloud does not have xyz fields"); - return false; - } - if (target_frame == cloud_in.header.frame_id) { - cloud_out = cloud_in; - return true; - } - Eigen::Matrix4f eigen_transform; - if (!get_transform(target_frame, cloud_in.header.frame_id, eigen_transform)) { - return false; - } - pcl_ros::transformPointCloud(eigen_transform, cloud_in, cloud_out); - cloud_out.header.frame_id = target_frame; - return true; - } - -private: - /** - * @brief Retrieves a transform between two static frames. - * - * This function attempts to retrieve a transform between the target frame and the source frame. - * If success, the transform matrix is set to the output parameter and the function returns true. - * Otherwise, transform matrix is set to identity and the function returns false. Transform - * Listener is destroyed after function call. - * - * @param target_frame The target frame. - * @param source_frame The source frame. - * @param eigen_transform The output Eigen transform matrix. It is set to the identity if the - * transform is not found. - * @return True if the transform was successfully retrieved, false otherwise. - */ - bool get_static_transform( - const std::string & target_frame, const std::string & source_frame, - Eigen::Matrix4f & eigen_transform) - { - if ( - std::find(warn_frames.begin(), warn_frames.end(), target_frame) != warn_frames.end() || - std::find(warn_frames.begin(), warn_frames.end(), source_frame) != warn_frames.end()) { - RCLCPP_WARN( - node_->get_logger(), "Using %s -> %s transform. This may not be a static transform.", - target_frame.c_str(), source_frame.c_str()); - } - - auto key = std::make_pair(target_frame, source_frame); - auto key_inv = std::make_pair(source_frame, target_frame); - - // Check if the transform is already in the buffer - auto it = buffer_.find(key); - if (it != buffer_.end()) { - eigen_transform = it->second; - return true; - } - - // Check if the inverse transform is already in the buffer - auto it_inv = buffer_.find(key_inv); - if (it_inv != buffer_.end()) { - eigen_transform = it_inv->second.inverse(); - buffer_[key] = eigen_transform; - return true; - } - - // Check if transform is needed - if (target_frame == source_frame) { - eigen_transform = Eigen::Matrix4f::Identity(); - buffer_[key] = eigen_transform; - return true; - } - - // Get the transform from the TF tree - tf_listener_ = std::make_unique(node_); - auto tf = tf_listener_->get_transform( - target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration(1000ms)); - tf_listener_.reset(); - RCLCPP_DEBUG( - node_->get_logger(), "Trying to enqueue %s -> %s transform to static TFs buffer...", - target_frame.c_str(), source_frame.c_str()); - if (tf == nullptr) { - eigen_transform = Eigen::Matrix4f::Identity(); - return false; - } - pcl_ros::transformAsMatrix(*tf, eigen_transform); - buffer_[key] = eigen_transform; - return true; - } - - /** @brief Retrieves a transform between two dynamic frames. - * - * This function attempts to retrieve a transform between the target frame and the source frame. - * If successful, the transformation matrix is assigned to the output parameter, and the function - * returns true. Otherwise, the transformation matrix is set to the identity and the function - * returns false. - * - * @param target_frame The target frame. - * @param source_frame The source frame. - * @param eigen_transform The output Eigen transformation matrix. It is set to the identity if the - * transform is not found. - * @return True if the transform was successfully retrieved, false otherwise. - */ - bool get_dynamic_transform( - const std::string & target_frame, const std::string & source_frame, - Eigen::Matrix4f & eigen_transform) - { - auto tf = tf_listener_->get_transform( - target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration(1000ms)); - if (tf == nullptr) { - eigen_transform = Eigen::Matrix4f::Identity(); - return false; - } - pcl_ros::transformAsMatrix(*tf, eigen_transform); - return true; - } - TFMap buffer_; - rclcpp::Node * const node_; - std::unique_ptr tf_listener_; - std::function get_transform_; -}; +using namespace autoware_utils_pcl; // NOLINT(build/namespaces) } // namespace autoware_utils diff --git a/autoware_utils/include/autoware_utils/ros/pcl_conversion.hpp b/autoware_utils/include/autoware_utils/ros/pcl_conversion.hpp index 77c5c6b..1afc814 100644 --- a/autoware_utils/include/autoware_utils/ros/pcl_conversion.hpp +++ b/autoware_utils/include/autoware_utils/ros/pcl_conversion.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2025 The Autoware Contributors // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -15,57 +15,12 @@ #ifndef AUTOWARE_UTILS__ROS__PCL_CONVERSION_HPP_ #define AUTOWARE_UTILS__ROS__PCL_CONVERSION_HPP_ -#include -#include - -#include +#include namespace autoware_utils { -/** - * @brief a faster implementation of converting sensor_msgs::msg::PointCloud2 to - * pcl::PointCloud and transform the cloud - * - * @tparam Scalar - * @param cloud input PointCloud2 message - * @param pcl_cloud output transformed pcl cloud - * @param transform eigen transformation matrix - */ -template -void transform_point_cloud_from_ros_msg( - const sensor_msgs::msg::PointCloud2 & cloud, pcl::PointCloud & pcl_cloud, - const Eigen::Matrix & transform) -{ - // Copy info fields - pcl_conversions::toPCL(cloud.header, pcl_cloud.header); - pcl_cloud.width = cloud.width; - pcl_cloud.height = cloud.height; - pcl_cloud.is_dense = cloud.is_dense == 1; - - pcl::MsgFieldMap field_map; - std::vector msg_fields; - pcl_conversions::toPCL(cloud.fields, msg_fields); - pcl::createMapping(msg_fields, field_map); - - // transform point data - std::uint32_t num_points = cloud.width * cloud.height; - pcl_cloud.points.resize(num_points); - std::uint8_t * cloud_data = reinterpret_cast(&pcl_cloud.points[0]); - pcl::detail::Transformer tf(transform); - for (std::uint32_t row = 0; row < cloud.height; ++row) { - const std::uint8_t * row_data = &cloud.data[row * cloud.row_step]; - for (std::uint32_t col = 0; col < cloud.width; ++col) { - const std::uint8_t * msg_data = row_data + col * cloud.point_step; - for (const pcl::detail::FieldMapping & mapping : field_map) { - const float * msg_ptr = reinterpret_cast(msg_data); - float * pcl_ptr = reinterpret_cast(cloud_data + mapping.struct_offset); - tf.se3(msg_ptr, pcl_ptr); - } - cloud_data += sizeof(pcl::PointXYZ); - } - } -} +using namespace autoware_utils_pcl; // NOLINT(build/namespaces) } // namespace autoware_utils diff --git a/autoware_utils/include/autoware_utils/ros/transform_listener.hpp b/autoware_utils/include/autoware_utils/ros/transform_listener.hpp index 4b75545..a2e690f 100644 --- a/autoware_utils/include/autoware_utils/ros/transform_listener.hpp +++ b/autoware_utils/include/autoware_utils/ros/transform_listener.hpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// Copyright 2025 The Autoware Contributors // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -15,73 +15,13 @@ #ifndef AUTOWARE_UTILS__ROS__TRANSFORM_LISTENER_HPP_ #define AUTOWARE_UTILS__ROS__TRANSFORM_LISTENER_HPP_ -#include - -#include - -#include -#include -#include - -#include -#include +#include namespace autoware_utils { -class TransformListener -{ -public: - explicit TransformListener(rclcpp::Node * node) - : clock_(node->get_clock()), logger_(node->get_logger()) - { - tf_buffer_ = std::make_shared(clock_); - auto timer_interface = std::make_shared( - node->get_node_base_interface(), node->get_node_timers_interface()); - tf_buffer_->setCreateTimerInterface(timer_interface); - tf_listener_ = std::make_shared(*tf_buffer_); - } - - geometry_msgs::msg::TransformStamped::ConstSharedPtr get_latest_transform( - const std::string & from, const std::string & to) - { - geometry_msgs::msg::TransformStamped tf; - try { - tf = tf_buffer_->lookupTransform(from, to, tf2::TimePointZero); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_THROTTLE( - logger_, *clock_, 5000, "failed to get transform from %s to %s: %s", from.c_str(), - to.c_str(), ex.what()); - return {}; - } - - return std::make_shared(tf); - } - - geometry_msgs::msg::TransformStamped::ConstSharedPtr get_transform( - const std::string & from, const std::string & to, const rclcpp::Time & time, - const rclcpp::Duration & duration) - { - geometry_msgs::msg::TransformStamped tf; - try { - tf = tf_buffer_->lookupTransform(from, to, time, duration); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_THROTTLE( - logger_, *clock_, 5000, "failed to get transform from %s to %s: %s", from.c_str(), - to.c_str(), ex.what()); - return {}; - } - - return std::make_shared(tf); - } - rclcpp::Logger get_logger() { return logger_; } +using namespace autoware_utils_geometry; // NOLINT(build/namespaces) -private: - rclcpp::Clock::SharedPtr clock_; - rclcpp::Logger logger_; - std::shared_ptr tf_buffer_; - std::shared_ptr tf_listener_; -}; } // namespace autoware_utils #endif // AUTOWARE_UTILS__ROS__TRANSFORM_LISTENER_HPP_ diff --git a/autoware_utils/include/autoware_utils/transform/transforms.hpp b/autoware_utils/include/autoware_utils/transform/transforms.hpp index 042d67e..bfb1e00 100644 --- a/autoware_utils/include/autoware_utils/transform/transforms.hpp +++ b/autoware_utils/include/autoware_utils/transform/transforms.hpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// Copyright 2025 The Autoware Contributors // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -15,37 +15,13 @@ #ifndef AUTOWARE_UTILS__TRANSFORM__TRANSFORMS_HPP_ #define AUTOWARE_UTILS__TRANSFORM__TRANSFORMS_HPP_ -#include -#include - -#include -#include +#include namespace autoware_utils { -template -void transform_pointcloud( - const pcl::PointCloud & cloud_in, pcl::PointCloud & cloud_out, - const Eigen::Matrix & transform) -{ - if (cloud_in.empty() || cloud_in.width == 0) { - RCLCPP_WARN(rclcpp::get_logger("transform_pointcloud"), "input point cloud is empty!"); - } else { - pcl::transformPointCloud(cloud_in, cloud_out, transform); - } -} -template -void transform_pointcloud( - const pcl::PointCloud & cloud_in, pcl::PointCloud & cloud_out, - const Eigen::Affine3f & transform) -{ - if (cloud_in.empty() || cloud_in.width == 0) { - RCLCPP_WARN(rclcpp::get_logger("transform_pointcloud"), "input point cloud is empty!"); - } else { - pcl::transformPointCloud(cloud_in, cloud_out, transform); - } -} +using namespace autoware_utils_pcl; // NOLINT(build/namespaces) + } // namespace autoware_utils #endif // AUTOWARE_UTILS__TRANSFORM__TRANSFORMS_HPP_ diff --git a/autoware_utils/package.xml b/autoware_utils/package.xml index fa716d3..9b61de3 100644 --- a/autoware_utils/package.xml +++ b/autoware_utils/package.xml @@ -8,6 +8,7 @@ Ryohsuke Mitsudome Esteve Fernandez Yutaka Kondo + Takagi, Isamu Apache License 2.0 ament_cmake_auto @@ -18,14 +19,14 @@ autoware_internal_planning_msgs autoware_perception_msgs autoware_planning_msgs + autoware_utils_geometry + autoware_utils_pcl autoware_vehicle_msgs builtin_interfaces diagnostic_msgs geometry_msgs libboost-system-dev logging_demo - pcl_conversions - pcl_ros rclcpp tf2 tf2_eigen diff --git a/autoware_utils_geometry/CMakeLists.txt b/autoware_utils_geometry/CMakeLists.txt new file mode 100644 index 0000000..4f98e18 --- /dev/null +++ b/autoware_utils_geometry/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_utils_geometry) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +if(BUILD_TESTING) +endif() + +ament_auto_package() diff --git a/autoware_utils_geometry/README.md b/autoware_utils_geometry/README.md new file mode 100644 index 0000000..4fe9ee8 --- /dev/null +++ b/autoware_utils_geometry/README.md @@ -0,0 +1,11 @@ +# autoware_utils_geometry + +## Overview + +The **autoware_utils** library is a comprehensive toolkit designed to facilitate the development of autonomous driving applications. +This package provides essential utilities for geometry. +It is extensively used in the Autoware project to handle common tasks such as geometric calculations and message conversions. + +## Design + +- **`transform_listener.hpp`**: Manages transformation listeners. diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/transform_listener.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/transform_listener.hpp new file mode 100644 index 0000000..3b006db --- /dev/null +++ b/autoware_utils_geometry/include/autoware_utils_geometry/transform_listener.hpp @@ -0,0 +1,87 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS_GEOMETRY__TRANSFORM_LISTENER_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__TRANSFORM_LISTENER_HPP_ + +#include + +#include + +#include +#include +#include + +#include +#include + +namespace autoware_utils_geometry +{ +class TransformListener +{ +public: + explicit TransformListener(rclcpp::Node * node) + : clock_(node->get_clock()), logger_(node->get_logger()) + { + tf_buffer_ = std::make_shared(clock_); + auto timer_interface = std::make_shared( + node->get_node_base_interface(), node->get_node_timers_interface()); + tf_buffer_->setCreateTimerInterface(timer_interface); + tf_listener_ = std::make_shared(*tf_buffer_); + } + + geometry_msgs::msg::TransformStamped::ConstSharedPtr get_latest_transform( + const std::string & from, const std::string & to) + { + geometry_msgs::msg::TransformStamped tf; + try { + tf = tf_buffer_->lookupTransform(from, to, tf2::TimePointZero); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_THROTTLE( + logger_, *clock_, 5000, "failed to get transform from %s to %s: %s", from.c_str(), + to.c_str(), ex.what()); + return {}; + } + + return std::make_shared(tf); + } + + geometry_msgs::msg::TransformStamped::ConstSharedPtr get_transform( + const std::string & from, const std::string & to, const rclcpp::Time & time, + const rclcpp::Duration & duration) + { + geometry_msgs::msg::TransformStamped tf; + try { + tf = tf_buffer_->lookupTransform(from, to, time, duration); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_THROTTLE( + logger_, *clock_, 5000, "failed to get transform from %s to %s: %s", from.c_str(), + to.c_str(), ex.what()); + return {}; + } + + return std::make_shared(tf); + } + + rclcpp::Logger get_logger() { return logger_; } + +private: + rclcpp::Clock::SharedPtr clock_; + rclcpp::Logger logger_; + std::shared_ptr tf_buffer_; + std::shared_ptr tf_listener_; +}; +} // namespace autoware_utils_geometry + +#endif // AUTOWARE_UTILS_GEOMETRY__TRANSFORM_LISTENER_HPP_ diff --git a/autoware_utils_geometry/package.xml b/autoware_utils_geometry/package.xml new file mode 100644 index 0000000..98fa33c --- /dev/null +++ b/autoware_utils_geometry/package.xml @@ -0,0 +1,27 @@ + + + + autoware_utils_geometry + 1.1.0 + The autoware_utils_geometry package + Jian Kang + Ryohsuke Mitsudome + Esteve Fernandez + Yutaka Kondo + Takagi, Isamu + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + geometry_msgs + rclcpp + tf2_ros + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/autoware_utils_pcl/CMakeLists.txt b/autoware_utils_pcl/CMakeLists.txt new file mode 100644 index 0000000..516f373 --- /dev/null +++ b/autoware_utils_pcl/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_utils_pcl) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +if(BUILD_TESTING) +endif() + +ament_auto_package() diff --git a/autoware_utils_pcl/README.md b/autoware_utils_pcl/README.md new file mode 100644 index 0000000..296c52b --- /dev/null +++ b/autoware_utils_pcl/README.md @@ -0,0 +1,77 @@ +# autoware_utils_pcl + +## Overview + +The **autoware_utils** library is a comprehensive toolkit designed to facilitate the development of autonomous driving applications. +This package provides essential utilities for point cloud. +It is extensively used in the Autoware project to handle common tasks such as point cloud transformations. + +## Design + +- **`managed_transform_buffer.hpp`**: A managed buffer for handling static and dynamic transforms. +- **`pcl_conversion.hpp`**: Efficient conversion and transformation of PointCloud2 messages to PCL point clouds. +- **`transforms.hpp`**: Efficient methods for transforming and manipulating point clouds. + +## Example Code Snippets + +### Transform Point Clouds with ManagedTransformBuffer + +```cpp +#include +#include +#include + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("transform_node"); + + // Initialize ManagedTransformBuffer + autoware_utils::ManagedTransformBuffer transform_buffer(node, false); + + // Load point cloud data + sensor_msgs::msg::PointCloud2 cloud_in; // Assume this is populated with data + sensor_msgs::msg::PointCloud2 cloud_out; + + // Transform point cloud from "base_link" to "map" frame + if (transform_buffer.transform_pointcloud("map", cloud_in, cloud_out)) { + RCLCPP_INFO(node->get_logger(), "Point cloud transformed successfully."); + } else { + RCLCPP_ERROR(node->get_logger(), "Failed to transform point cloud."); + } + + rclcpp::shutdown(); + return 0; +} +``` + +### Efficient Point Cloud Conversion with pcl_conversion.hpp + +```cpp +#include +#include +#include +#include +#include +#include + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("pcl_conversion_node"); + + // Load point cloud data + sensor_msgs::msg::PointCloud2 cloud_in; // Assume this is populated with data + pcl::PointCloud pcl_cloud; + + // Define transformation matrix + Eigen::Matrix4f transform = Eigen::Matrix4f::Identity(); + // Populate transform matrix with actual values + + // Convert and transform point cloud + autoware_utils::transform_point_cloud_from_ros_msg(cloud_in, pcl_cloud, transform); + + rclcpp::shutdown(); + return 0; +} +``` diff --git a/autoware_utils_pcl/include/autoware_utils_pcl/managed_transform_buffer.hpp b/autoware_utils_pcl/include/autoware_utils_pcl/managed_transform_buffer.hpp new file mode 100644 index 0000000..9f5e906 --- /dev/null +++ b/autoware_utils_pcl/include/autoware_utils_pcl/managed_transform_buffer.hpp @@ -0,0 +1,227 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS_PCL__MANAGED_TRANSFORM_BUFFER_HPP_ +#define AUTOWARE_UTILS_PCL__MANAGED_TRANSFORM_BUFFER_HPP_ + +#include +#include +#include +#include + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace std +{ +template <> +struct hash> +{ + size_t operator()(const std::pair & p) const + { + size_t h1 = std::hash{}(p.first); + size_t h2 = std::hash{}(p.second); + return h1 ^ (h2 << 1u); + } +}; +} // namespace std + +namespace autoware_utils_pcl +{ +using std::chrono_literals::operator""ms; +using Key = std::pair; +struct PairEqual +{ + bool operator()(const Key & p1, const Key & p2) const + { + return p1.first == p2.first && p1.second == p2.second; + } +}; +using TFMap = std::unordered_map, PairEqual>; +constexpr std::array warn_frames = {"map", "odom", "world"}; + +class ManagedTransformBuffer +{ +public: + explicit ManagedTransformBuffer(rclcpp::Node * node, const bool & has_static_tf_only) + : node_(node) + { + if (has_static_tf_only) { + get_transform_ = [this]( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) { + return get_static_transform(target_frame, source_frame, eigen_transform); + }; + } else { + tf_listener_ = std::make_unique(node); + get_transform_ = [this]( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) { + return get_dynamic_transform(target_frame, source_frame, eigen_transform); + }; + } + } + + bool get_transform( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) + { + return get_transform_(target_frame, source_frame, eigen_transform); + } + + /** + * Transforms a point cloud from one frame to another. + * + * @param target_frame The target frame to transform the point cloud to. + * @param cloud_in The input point cloud to be transformed. + * @param cloud_out The transformed point cloud. + * @return True if the transformation is successful, false otherwise. + */ + bool transform_pointcloud( + const std::string & target_frame, const sensor_msgs::msg::PointCloud2 & cloud_in, + sensor_msgs::msg::PointCloud2 & cloud_out) + { + if ( + pcl::getFieldIndex(cloud_in, "x") == -1 || pcl::getFieldIndex(cloud_in, "y") == -1 || + pcl::getFieldIndex(cloud_in, "z") == -1) { + RCLCPP_ERROR(node_->get_logger(), "Input pointcloud does not have xyz fields"); + return false; + } + if (target_frame == cloud_in.header.frame_id) { + cloud_out = cloud_in; + return true; + } + Eigen::Matrix4f eigen_transform; + if (!get_transform(target_frame, cloud_in.header.frame_id, eigen_transform)) { + return false; + } + pcl_ros::transformPointCloud(eigen_transform, cloud_in, cloud_out); + cloud_out.header.frame_id = target_frame; + return true; + } + +private: + /** + * @brief Retrieves a transform between two static frames. + * + * This function attempts to retrieve a transform between the target frame and the source frame. + * If success, the transform matrix is set to the output parameter and the function returns true. + * Otherwise, transform matrix is set to identity and the function returns false. Transform + * Listener is destroyed after function call. + * + * @param target_frame The target frame. + * @param source_frame The source frame. + * @param eigen_transform The output Eigen transform matrix. It is set to the identity if the + * transform is not found. + * @return True if the transform was successfully retrieved, false otherwise. + */ + bool get_static_transform( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) + { + if ( + std::find(warn_frames.begin(), warn_frames.end(), target_frame) != warn_frames.end() || + std::find(warn_frames.begin(), warn_frames.end(), source_frame) != warn_frames.end()) { + RCLCPP_WARN( + node_->get_logger(), "Using %s -> %s transform. This may not be a static transform.", + target_frame.c_str(), source_frame.c_str()); + } + + auto key = std::make_pair(target_frame, source_frame); + auto key_inv = std::make_pair(source_frame, target_frame); + + // Check if the transform is already in the buffer + auto it = buffer_.find(key); + if (it != buffer_.end()) { + eigen_transform = it->second; + return true; + } + + // Check if the inverse transform is already in the buffer + auto it_inv = buffer_.find(key_inv); + if (it_inv != buffer_.end()) { + eigen_transform = it_inv->second.inverse(); + buffer_[key] = eigen_transform; + return true; + } + + // Check if transform is needed + if (target_frame == source_frame) { + eigen_transform = Eigen::Matrix4f::Identity(); + buffer_[key] = eigen_transform; + return true; + } + + // Get the transform from the TF tree + tf_listener_ = std::make_unique(node_); + auto tf = tf_listener_->get_transform( + target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration(1000ms)); + tf_listener_.reset(); + RCLCPP_DEBUG( + node_->get_logger(), "Trying to enqueue %s -> %s transform to static TFs buffer...", + target_frame.c_str(), source_frame.c_str()); + if (tf == nullptr) { + eigen_transform = Eigen::Matrix4f::Identity(); + return false; + } + pcl_ros::transformAsMatrix(*tf, eigen_transform); + buffer_[key] = eigen_transform; + return true; + } + + /** @brief Retrieves a transform between two dynamic frames. + * + * This function attempts to retrieve a transform between the target frame and the source frame. + * If successful, the transformation matrix is assigned to the output parameter, and the function + * returns true. Otherwise, the transformation matrix is set to the identity and the function + * returns false. + * + * @param target_frame The target frame. + * @param source_frame The source frame. + * @param eigen_transform The output Eigen transformation matrix. It is set to the identity if the + * transform is not found. + * @return True if the transform was successfully retrieved, false otherwise. + */ + bool get_dynamic_transform( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) + { + auto tf = tf_listener_->get_transform( + target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration(1000ms)); + if (tf == nullptr) { + eigen_transform = Eigen::Matrix4f::Identity(); + return false; + } + pcl_ros::transformAsMatrix(*tf, eigen_transform); + return true; + } + + TFMap buffer_; + rclcpp::Node * const node_; + std::unique_ptr tf_listener_; + std::function get_transform_; +}; + +} // namespace autoware_utils_pcl + +#endif // AUTOWARE_UTILS_PCL__MANAGED_TRANSFORM_BUFFER_HPP_ diff --git a/autoware_utils_pcl/include/autoware_utils_pcl/pcl_conversion.hpp b/autoware_utils_pcl/include/autoware_utils_pcl/pcl_conversion.hpp new file mode 100644 index 0000000..ddfe3b9 --- /dev/null +++ b/autoware_utils_pcl/include/autoware_utils_pcl/pcl_conversion.hpp @@ -0,0 +1,72 @@ +// Copyright 2023 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS_PCL__PCL_CONVERSION_HPP_ +#define AUTOWARE_UTILS_PCL__PCL_CONVERSION_HPP_ + +#include +#include + +#include + +namespace autoware_utils_pcl +{ +/** + * @brief a faster implementation of converting sensor_msgs::msg::PointCloud2 to + * pcl::PointCloud and transform the cloud + * + * @tparam Scalar + * @param cloud input PointCloud2 message + * @param pcl_cloud output transformed pcl cloud + * @param transform eigen transformation matrix + */ +template +void transform_point_cloud_from_ros_msg( + const sensor_msgs::msg::PointCloud2 & cloud, pcl::PointCloud & pcl_cloud, + const Eigen::Matrix & transform) +{ + // Copy info fields + pcl_conversions::toPCL(cloud.header, pcl_cloud.header); + pcl_cloud.width = cloud.width; + pcl_cloud.height = cloud.height; + pcl_cloud.is_dense = cloud.is_dense == 1; + + pcl::MsgFieldMap field_map; + std::vector msg_fields; + pcl_conversions::toPCL(cloud.fields, msg_fields); + pcl::createMapping(msg_fields, field_map); + + // transform point data + std::uint32_t num_points = cloud.width * cloud.height; + pcl_cloud.points.resize(num_points); + std::uint8_t * cloud_data = reinterpret_cast(&pcl_cloud.points[0]); + pcl::detail::Transformer tf(transform); + + for (std::uint32_t row = 0; row < cloud.height; ++row) { + const std::uint8_t * row_data = &cloud.data[row * cloud.row_step]; + for (std::uint32_t col = 0; col < cloud.width; ++col) { + const std::uint8_t * msg_data = row_data + col * cloud.point_step; + for (const pcl::detail::FieldMapping & mapping : field_map) { + const float * msg_ptr = reinterpret_cast(msg_data); + float * pcl_ptr = reinterpret_cast(cloud_data + mapping.struct_offset); + tf.se3(msg_ptr, pcl_ptr); + } + cloud_data += sizeof(pcl::PointXYZ); + } + } +} + +} // namespace autoware_utils_pcl + +#endif // AUTOWARE_UTILS_PCL__PCL_CONVERSION_HPP_ diff --git a/autoware_utils_pcl/include/autoware_utils_pcl/transforms.hpp b/autoware_utils_pcl/include/autoware_utils_pcl/transforms.hpp new file mode 100644 index 0000000..3a340f9 --- /dev/null +++ b/autoware_utils_pcl/include/autoware_utils_pcl/transforms.hpp @@ -0,0 +1,51 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS_PCL__TRANSFORMS_HPP_ +#define AUTOWARE_UTILS_PCL__TRANSFORMS_HPP_ + +#include +#include + +#include +#include + +namespace autoware_utils_pcl +{ +template +void transform_pointcloud( + const pcl::PointCloud & cloud_in, pcl::PointCloud & cloud_out, + const Eigen::Matrix & transform) +{ + if (cloud_in.empty() || cloud_in.width == 0) { + RCLCPP_WARN(rclcpp::get_logger("transform_pointcloud"), "input point cloud is empty!"); + } else { + pcl::transformPointCloud(cloud_in, cloud_out, transform); + } +} + +template +void transform_pointcloud( + const pcl::PointCloud & cloud_in, pcl::PointCloud & cloud_out, + const Eigen::Affine3f & transform) +{ + if (cloud_in.empty() || cloud_in.width == 0) { + RCLCPP_WARN(rclcpp::get_logger("transform_pointcloud"), "input point cloud is empty!"); + } else { + pcl::transformPointCloud(cloud_in, cloud_out, transform); + } +} +} // namespace autoware_utils_pcl + +#endif // AUTOWARE_UTILS_PCL__TRANSFORMS_HPP_ diff --git a/autoware_utils_pcl/package.xml b/autoware_utils_pcl/package.xml new file mode 100644 index 0000000..beb3200 --- /dev/null +++ b/autoware_utils_pcl/package.xml @@ -0,0 +1,27 @@ + + + + autoware_utils_pcl + 1.1.0 + The autoware_utils_pcl package + Jian Kang + Ryohsuke Mitsudome + Esteve Fernandez + Yutaka Kondo + Takagi, Isamu + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_utils_geometry + pcl_conversions + pcl_ros + + ament_lint_auto + autoware_lint_common + + + ament_cmake + +