diff --git a/src/perception/ground_segmentation/CMakeLists.txt b/src/perception/ground_segmentation/CMakeLists.txt new file mode 100644 index 0000000..2688ceb --- /dev/null +++ b/src/perception/ground_segmentation/CMakeLists.txt @@ -0,0 +1,37 @@ +cmake_minimum_required(VERSION 3.5) +project(ground_segmentation) + +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_EXTENSIONS OFF) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +include_directories(include) + +ament_auto_add_library(ground_segmentation SHARED + src/ground_filter.cpp + src/ransac_ground_filter/ransac_ground_filter.cpp +) + +rclcpp_components_register_node(ground_segmentation + PLUGIN "ground_segmentation::ransac_ground_filter::RANSACGroundFilter" + EXECUTABLE ransac_ground_filter_node +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package(INSTALL_TO_SHARE + config + launch +) diff --git a/src/perception/ground_segmentation/config/ransac_ground_filter.param.yaml b/src/perception/ground_segmentation/config/ransac_ground_filter.param.yaml new file mode 100644 index 0000000..5a42671 --- /dev/null +++ b/src/perception/ground_segmentation/config/ransac_ground_filter.param.yaml @@ -0,0 +1,7 @@ +/**: + ros__parameters: + footprint_frame: base_link + leaf_size: 0.1 + distance_threshold: 0.3 + max_iterations: 1000 + slope_threshold: 10.0 diff --git a/src/perception/ground_segmentation/include/ground_segmentation/ground_filter.hpp b/src/perception/ground_segmentation/include/ground_segmentation/ground_filter.hpp new file mode 100644 index 0000000..9370525 --- /dev/null +++ b/src/perception/ground_segmentation/include/ground_segmentation/ground_filter.hpp @@ -0,0 +1,56 @@ +// Copyright 2024 Fool Stuck Engineers +// +// 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 GROUND_SEGMENTATION__GROUND_FILTER_HPP_ +#define GROUND_SEGMENTATION__GROUND_FILTER_HPP_ + +#include +#include +#include + +#include + +#include +#include + +#include + +namespace ground_segmentation +{ + +using PointCloud2 = sensor_msgs::msg::PointCloud2; + +class GroundFilter : public rclcpp::Node +{ +public: + explicit GroundFilter(const std::string & node_name, const rclcpp::NodeOptions & options); + +protected: + virtual bool filter(const PointCloud2 & input, PointCloud2 & output) = 0; + [[nodiscard]] bool try_transform_pointcloud( + const std::string & target_frame, const PointCloud2 & input, PointCloud2 & output, + const double timeout = 1.0); + +private: + void input_callback(const PointCloud2::SharedPtr msg); + + rclcpp::Subscription::SharedPtr input_sub_; + rclcpp::Publisher::SharedPtr output_pub_; + + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; +}; +} // namespace ground_segmentation + +#endif // GROUND_SEGMENTATION__GROUND_FILTER_HPP_ diff --git a/src/perception/ground_segmentation/include/ground_segmentation/ransac_ground_filter/ransac_ground_filter.hpp b/src/perception/ground_segmentation/include/ground_segmentation/ransac_ground_filter/ransac_ground_filter.hpp new file mode 100644 index 0000000..7e903a2 --- /dev/null +++ b/src/perception/ground_segmentation/include/ground_segmentation/ransac_ground_filter/ransac_ground_filter.hpp @@ -0,0 +1,52 @@ +// Copyright 2024 Fool Stuck Engineers +// +// 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 GROUND_SEGMENTATION__RANSAC_GROUND_FILTER__RANSAC_GROUND_FILTER_HPP_ +#define GROUND_SEGMENTATION__RANSAC_GROUND_FILTER__RANSAC_GROUND_FILTER_HPP_ + +#include "ground_segmentation/ground_filter.hpp" + +#include +#include +#include +#include + +#include + +namespace ground_segmentation::ransac_ground_filter +{ + +using PointType = pcl::PointXYZ; + +class RANSACGroundFilter : public GroundFilter +{ +public: + explicit RANSACGroundFilter(const rclcpp::NodeOptions & options); + +protected: + bool filter(const PointCloud2 & input, PointCloud2 & output) override; + +private: + Eigen::Vector3d unit_z_vec_ = Eigen::Vector3d::UnitZ(); + + std::string footprint_frame_; + double leaf_size_; + double distance_threshold_; + int max_iterations_; + double slope_threshold_rad_; +}; + +} // namespace ground_segmentation::ransac_ground_filter + +#endif // GROUND_SEGMENTATION__RANSAC_GROUND_FILTER__RANSAC_GROUND_FILTER_HPP_ diff --git a/src/perception/ground_segmentation/launch/ground_segmentation.launch.xml b/src/perception/ground_segmentation/launch/ground_segmentation.launch.xml new file mode 100644 index 0000000..741107e --- /dev/null +++ b/src/perception/ground_segmentation/launch/ground_segmentation.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/src/perception/ground_segmentation/package.xml b/src/perception/ground_segmentation/package.xml new file mode 100644 index 0000000..da0d65d --- /dev/null +++ b/src/perception/ground_segmentation/package.xml @@ -0,0 +1,24 @@ + + + + ground_segmentation + 0.0.0 + The ground_segmentation package + Akiro Harada + + Apache 2 + + ament_cmake_auto + + pcl_ros + rclcpp + rclcpp_components + sensor_msgs + tf2_eigen + tf2_ros + ament_lint_auto + + + ament_cmake + + diff --git a/src/perception/ground_segmentation/src/ground_filter.cpp b/src/perception/ground_segmentation/src/ground_filter.cpp new file mode 100644 index 0000000..6086bbc --- /dev/null +++ b/src/perception/ground_segmentation/src/ground_filter.cpp @@ -0,0 +1,57 @@ +// Copyright 2024 Fool Stuck Engineers +// +// 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. + +#include "ground_segmentation/ground_filter.hpp" + +namespace ground_segmentation +{ +GroundFilter::GroundFilter(const std::string & node_name, const rclcpp::NodeOptions & options) +: Node(node_name, options), tf_buffer_(get_clock()), tf_listener_(tf_buffer_) +{ + input_sub_ = create_subscription( + "~/input/points", 1, std::bind(&GroundFilter::input_callback, this, std::placeholders::_1)); + output_pub_ = create_publisher("~/output/points", 1); +} + +bool GroundFilter::try_transform_pointcloud( + const std::string & target_frame, const PointCloud2 & input, PointCloud2 & output, + const double timeout) +{ + if (input.header.frame_id == target_frame) { + output = input; + return true; + } + + geometry_msgs::msg::TransformStamped transform; + try { + transform = tf_buffer_.lookupTransform( + target_frame, input.header.frame_id, input.header.stamp, tf2::durationFromSec(timeout)); + } catch (const tf2::TransformException & e) { + return false; + } + + Eigen::Matrix4f transform_matrix = tf2::transformToEigen(transform).matrix().cast(); + pcl_ros::transformPointCloud(transform_matrix, input, output); + output.header.frame_id = target_frame; + + return true; +} + +void GroundFilter::input_callback(const PointCloud2::SharedPtr msg) +{ + PointCloud2 output; + if (!filter(*msg, output)) return; + output_pub_->publish(output); +} +} // namespace ground_segmentation diff --git a/src/perception/ground_segmentation/src/ransac_ground_filter/ransac_ground_filter.cpp b/src/perception/ground_segmentation/src/ransac_ground_filter/ransac_ground_filter.cpp new file mode 100644 index 0000000..8eae51e --- /dev/null +++ b/src/perception/ground_segmentation/src/ransac_ground_filter/ransac_ground_filter.cpp @@ -0,0 +1,114 @@ +// Copyright 2024 Fool Stuck Engineers +// +// 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. + +#include "ground_segmentation/ransac_ground_filter/ransac_ground_filter.hpp" + +namespace ground_segmentation::ransac_ground_filter +{ +RANSACGroundFilter::RANSACGroundFilter(const rclcpp::NodeOptions & options) +: GroundFilter("ransac_ground_filter", options) +{ + footprint_frame_ = declare_parameter("footprint_frame", "base_link"); + leaf_size_ = declare_parameter("leaf_size", 0.1); + distance_threshold_ = declare_parameter("distance_threshold", 0.1); + max_iterations_ = declare_parameter("max_iterations", 1000); + slope_threshold_rad_ = declare_parameter("slope_threshold", 10.0) * M_PI / 180.0; +} + +bool RANSACGroundFilter::filter(const PointCloud2 & input, PointCloud2 & output) +{ + // Transform input to base_link + PointCloud2::SharedPtr input_transformed(new PointCloud2); + { + if (!try_transform_pointcloud(footprint_frame_, input, *input_transformed)) return false; + } + + // Convert to PCL + pcl::PointCloud::Ptr input_cloud(new pcl::PointCloud); + { + pcl::fromROSMsg(*input_transformed, *input_cloud); + } + + // Downsample the input cloud + pcl::PointCloud::Ptr downsampled_cloud(new pcl::PointCloud); + { + pcl::VoxelGrid voxel_grid; + voxel_grid.setInputCloud(input_cloud); + voxel_grid.setLeafSize(leaf_size_, leaf_size_, leaf_size_); + voxel_grid.filter(*downsampled_cloud); + } + + // Apply RANSAC + pcl::PointIndices::Ptr inliers(new pcl::PointIndices); + pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients); + { + pcl::SACSegmentation seg; + seg.setOptimizeCoefficients(true); + seg.setModelType(pcl::SACMODEL_PLANE); + seg.setMethodType(pcl::SAC_RANSAC); + seg.setMaxIterations(max_iterations_); + seg.setDistanceThreshold(distance_threshold_); + + seg.setInputCloud(downsampled_cloud); + seg.segment(*inliers, *coefficients); + } + + // Return input as output if no ground plane is found + if (coefficients->values.empty()) { + RCLCPP_WARN(get_logger(), "Failed to find a ground plane"); + output = input; + return true; + } + + // Filter tilted plane + { + Eigen::Vector3d normal( + coefficients->values[0], coefficients->values[1], coefficients->values[2]); + const auto slope_rad = + std::abs(std::acos(normal.dot(unit_z_vec_) / (normal.norm() * unit_z_vec_.norm()))); + if (slope_rad > slope_threshold_rad_) { + output = input; + return true; + } + } + + // Extract ground points and obstacle points + pcl::PointCloud::Ptr ground_cloud(new pcl::PointCloud); + pcl::PointCloud::Ptr obstacle_cloud(new pcl::PointCloud); + { + pcl::ExtractIndices extract; + extract.setInputCloud(downsampled_cloud); + extract.setIndices(inliers); + + extract.setNegative(false); + extract.filter(*ground_cloud); + + extract.setNegative(true); + extract.filter(*obstacle_cloud); + } + + // Convert obstacle cloud to ROS message + { + PointCloud2 obstacle_cloud_msg; + pcl::toROSMsg(*obstacle_cloud, obstacle_cloud_msg); + obstacle_cloud_msg.header = input_transformed->header; + output = obstacle_cloud_msg; + } + + return true; +} +} // namespace ground_segmentation::ransac_ground_filter + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(ground_segmentation::ransac_ground_filter::RANSACGroundFilter)