Skip to content

Commit ca62f4a

Browse files
Autumn60Bey9434
andauthored
feat(perception): add ground segmentation with RANSAC (#123)
* create base class and sample inherited class Signed-off-by: Autumn60 <harada.akiro@gmail.com> * fix lookup Signed-off-by: Autumn60 <harada.akiro@gmail.com> * skip transform if input frame_id and target_frame are same Signed-off-by: Autumn60 <harada.akiro@gmail.com> * implement ransac filtering Signed-off-by: Autumn60 <harada.akiro@gmail.com> * create launch and config Signed-off-by: Autumn60 <harada.akiro@gmail.com> * fix depend Signed-off-by: Autumn60 <harada.akiro@gmail.com> --------- Signed-off-by: Autumn60 <harada.akiro@gmail.com> Co-authored-by: Bey9434 <134945706+Bey9434@users.noreply.github.com>
1 parent 94e6bb9 commit ca62f4a

File tree

8 files changed

+361
-0
lines changed

8 files changed

+361
-0
lines changed
Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
cmake_minimum_required(VERSION 3.5)
2+
project(ground_segmentation)
3+
4+
if(NOT CMAKE_CXX_STANDARD)
5+
set(CMAKE_CXX_STANDARD 14)
6+
set(CMAKE_CXX_STANDARD_REQUIRED ON)
7+
set(CMAKE_CXX_EXTENSIONS OFF)
8+
endif()
9+
10+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
11+
add_compile_options(-Wall -Wextra -Wpedantic)
12+
endif()
13+
14+
find_package(ament_cmake_auto REQUIRED)
15+
ament_auto_find_build_dependencies()
16+
17+
include_directories(include)
18+
19+
ament_auto_add_library(ground_segmentation SHARED
20+
src/ground_filter.cpp
21+
src/ransac_ground_filter/ransac_ground_filter.cpp
22+
)
23+
24+
rclcpp_components_register_node(ground_segmentation
25+
PLUGIN "ground_segmentation::ransac_ground_filter::RANSACGroundFilter"
26+
EXECUTABLE ransac_ground_filter_node
27+
)
28+
29+
if(BUILD_TESTING)
30+
find_package(ament_lint_auto REQUIRED)
31+
ament_lint_auto_find_test_dependencies()
32+
endif()
33+
34+
ament_auto_package(INSTALL_TO_SHARE
35+
config
36+
launch
37+
)
Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
/**:
2+
ros__parameters:
3+
footprint_frame: base_link
4+
leaf_size: 0.1
5+
distance_threshold: 0.3
6+
max_iterations: 1000
7+
slope_threshold: 10.0
Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
// Copyright 2024 Fool Stuck Engineers
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+
#ifndef GROUND_SEGMENTATION__GROUND_FILTER_HPP_
16+
#define GROUND_SEGMENTATION__GROUND_FILTER_HPP_
17+
18+
#include <pcl_ros/transforms.hpp>
19+
#include <rclcpp/rclcpp.hpp>
20+
#include <tf2_eigen/tf2_eigen.hpp>
21+
22+
#include <sensor_msgs/msg/point_cloud2.hpp>
23+
24+
#include <tf2_ros/buffer.h>
25+
#include <tf2_ros/transform_listener.h>
26+
27+
#include <string>
28+
29+
namespace ground_segmentation
30+
{
31+
32+
using PointCloud2 = sensor_msgs::msg::PointCloud2;
33+
34+
class GroundFilter : public rclcpp::Node
35+
{
36+
public:
37+
explicit GroundFilter(const std::string & node_name, const rclcpp::NodeOptions & options);
38+
39+
protected:
40+
virtual bool filter(const PointCloud2 & input, PointCloud2 & output) = 0;
41+
[[nodiscard]] bool try_transform_pointcloud(
42+
const std::string & target_frame, const PointCloud2 & input, PointCloud2 & output,
43+
const double timeout = 1.0);
44+
45+
private:
46+
void input_callback(const PointCloud2::SharedPtr msg);
47+
48+
rclcpp::Subscription<PointCloud2>::SharedPtr input_sub_;
49+
rclcpp::Publisher<PointCloud2>::SharedPtr output_pub_;
50+
51+
tf2_ros::Buffer tf_buffer_;
52+
tf2_ros::TransformListener tf_listener_;
53+
};
54+
} // namespace ground_segmentation
55+
56+
#endif // GROUND_SEGMENTATION__GROUND_FILTER_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
1+
// Copyright 2024 Fool Stuck Engineers
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+
#ifndef GROUND_SEGMENTATION__RANSAC_GROUND_FILTER__RANSAC_GROUND_FILTER_HPP_
16+
#define GROUND_SEGMENTATION__RANSAC_GROUND_FILTER__RANSAC_GROUND_FILTER_HPP_
17+
18+
#include "ground_segmentation/ground_filter.hpp"
19+
20+
#include <pcl/filters/extract_indices.h>
21+
#include <pcl/filters/voxel_grid.h>
22+
#include <pcl/segmentation/sac_segmentation.h>
23+
#include <pcl_conversions/pcl_conversions.h>
24+
25+
#include <string>
26+
27+
namespace ground_segmentation::ransac_ground_filter
28+
{
29+
30+
using PointType = pcl::PointXYZ;
31+
32+
class RANSACGroundFilter : public GroundFilter
33+
{
34+
public:
35+
explicit RANSACGroundFilter(const rclcpp::NodeOptions & options);
36+
37+
protected:
38+
bool filter(const PointCloud2 & input, PointCloud2 & output) override;
39+
40+
private:
41+
Eigen::Vector3d unit_z_vec_ = Eigen::Vector3d::UnitZ();
42+
43+
std::string footprint_frame_;
44+
double leaf_size_;
45+
double distance_threshold_;
46+
int max_iterations_;
47+
double slope_threshold_rad_;
48+
};
49+
50+
} // namespace ground_segmentation::ransac_ground_filter
51+
52+
#endif // GROUND_SEGMENTATION__RANSAC_GROUND_FILTER__RANSAC_GROUND_FILTER_HPP_
Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
<launch>
2+
<arg name="method" default="ransac"/>
3+
4+
<arg name="input_points_topic" default="/velodyne_points"/>
5+
<arg name="output_points_topic" default="/velodyne_points/obstacle"/>
6+
7+
<arg name="config_file" default="$(find-pkg-share ground_segmentation)/config/$(var method)_ground_filter.param.yaml"/>
8+
9+
<node pkg="ground_segmentation" name="$(var method)_ground_filter" exec="$(var method)_ground_filter_node" output="screen">
10+
<remap from="~/input/points" to="$(var input_points_topic)"/>
11+
<remap from="~/output/points" to="$(var output_points_topic)"/>
12+
<param from="$(var config_file)"/>
13+
</node>
14+
</launch>
Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>ground_segmentation</name>
5+
<version>0.0.0</version>
6+
<description>The ground_segmentation package</description>
7+
<maintainer email="harada.akiro@gmail.com">Akiro Harada</maintainer>
8+
9+
<license>Apache 2</license>
10+
11+
<buildtool_depend>ament_cmake_auto</buildtool_depend>
12+
13+
<depend>pcl_ros</depend>
14+
<depend>rclcpp</depend>
15+
<depend>rclcpp_components</depend>
16+
<depend>sensor_msgs</depend>
17+
<depend>tf2_eigen</depend>
18+
<depend>tf2_ros</depend>
19+
<test_depend>ament_lint_auto</test_depend>
20+
21+
<export>
22+
<build_type>ament_cmake</build_type>
23+
</export>
24+
</package>
Lines changed: 57 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
// Copyright 2024 Fool Stuck Engineers
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 "ground_segmentation/ground_filter.hpp"
16+
17+
namespace ground_segmentation
18+
{
19+
GroundFilter::GroundFilter(const std::string & node_name, const rclcpp::NodeOptions & options)
20+
: Node(node_name, options), tf_buffer_(get_clock()), tf_listener_(tf_buffer_)
21+
{
22+
input_sub_ = create_subscription<PointCloud2>(
23+
"~/input/points", 1, std::bind(&GroundFilter::input_callback, this, std::placeholders::_1));
24+
output_pub_ = create_publisher<PointCloud2>("~/output/points", 1);
25+
}
26+
27+
bool GroundFilter::try_transform_pointcloud(
28+
const std::string & target_frame, const PointCloud2 & input, PointCloud2 & output,
29+
const double timeout)
30+
{
31+
if (input.header.frame_id == target_frame) {
32+
output = input;
33+
return true;
34+
}
35+
36+
geometry_msgs::msg::TransformStamped transform;
37+
try {
38+
transform = tf_buffer_.lookupTransform(
39+
target_frame, input.header.frame_id, input.header.stamp, tf2::durationFromSec(timeout));
40+
} catch (const tf2::TransformException & e) {
41+
return false;
42+
}
43+
44+
Eigen::Matrix4f transform_matrix = tf2::transformToEigen(transform).matrix().cast<float>();
45+
pcl_ros::transformPointCloud(transform_matrix, input, output);
46+
output.header.frame_id = target_frame;
47+
48+
return true;
49+
}
50+
51+
void GroundFilter::input_callback(const PointCloud2::SharedPtr msg)
52+
{
53+
PointCloud2 output;
54+
if (!filter(*msg, output)) return;
55+
output_pub_->publish(output);
56+
}
57+
} // namespace ground_segmentation
Lines changed: 114 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,114 @@
1+
// Copyright 2024 Fool Stuck Engineers
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 "ground_segmentation/ransac_ground_filter/ransac_ground_filter.hpp"
16+
17+
namespace ground_segmentation::ransac_ground_filter
18+
{
19+
RANSACGroundFilter::RANSACGroundFilter(const rclcpp::NodeOptions & options)
20+
: GroundFilter("ransac_ground_filter", options)
21+
{
22+
footprint_frame_ = declare_parameter<std::string>("footprint_frame", "base_link");
23+
leaf_size_ = declare_parameter<double>("leaf_size", 0.1);
24+
distance_threshold_ = declare_parameter<double>("distance_threshold", 0.1);
25+
max_iterations_ = declare_parameter<int>("max_iterations", 1000);
26+
slope_threshold_rad_ = declare_parameter<double>("slope_threshold", 10.0) * M_PI / 180.0;
27+
}
28+
29+
bool RANSACGroundFilter::filter(const PointCloud2 & input, PointCloud2 & output)
30+
{
31+
// Transform input to base_link
32+
PointCloud2::SharedPtr input_transformed(new PointCloud2);
33+
{
34+
if (!try_transform_pointcloud(footprint_frame_, input, *input_transformed)) return false;
35+
}
36+
37+
// Convert to PCL
38+
pcl::PointCloud<PointType>::Ptr input_cloud(new pcl::PointCloud<PointType>);
39+
{
40+
pcl::fromROSMsg(*input_transformed, *input_cloud);
41+
}
42+
43+
// Downsample the input cloud
44+
pcl::PointCloud<PointType>::Ptr downsampled_cloud(new pcl::PointCloud<PointType>);
45+
{
46+
pcl::VoxelGrid<PointType> voxel_grid;
47+
voxel_grid.setInputCloud(input_cloud);
48+
voxel_grid.setLeafSize(leaf_size_, leaf_size_, leaf_size_);
49+
voxel_grid.filter(*downsampled_cloud);
50+
}
51+
52+
// Apply RANSAC
53+
pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
54+
pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
55+
{
56+
pcl::SACSegmentation<PointType> seg;
57+
seg.setOptimizeCoefficients(true);
58+
seg.setModelType(pcl::SACMODEL_PLANE);
59+
seg.setMethodType(pcl::SAC_RANSAC);
60+
seg.setMaxIterations(max_iterations_);
61+
seg.setDistanceThreshold(distance_threshold_);
62+
63+
seg.setInputCloud(downsampled_cloud);
64+
seg.segment(*inliers, *coefficients);
65+
}
66+
67+
// Return input as output if no ground plane is found
68+
if (coefficients->values.empty()) {
69+
RCLCPP_WARN(get_logger(), "Failed to find a ground plane");
70+
output = input;
71+
return true;
72+
}
73+
74+
// Filter tilted plane
75+
{
76+
Eigen::Vector3d normal(
77+
coefficients->values[0], coefficients->values[1], coefficients->values[2]);
78+
const auto slope_rad =
79+
std::abs(std::acos(normal.dot(unit_z_vec_) / (normal.norm() * unit_z_vec_.norm())));
80+
if (slope_rad > slope_threshold_rad_) {
81+
output = input;
82+
return true;
83+
}
84+
}
85+
86+
// Extract ground points and obstacle points
87+
pcl::PointCloud<PointType>::Ptr ground_cloud(new pcl::PointCloud<PointType>);
88+
pcl::PointCloud<PointType>::Ptr obstacle_cloud(new pcl::PointCloud<PointType>);
89+
{
90+
pcl::ExtractIndices<PointType> extract;
91+
extract.setInputCloud(downsampled_cloud);
92+
extract.setIndices(inliers);
93+
94+
extract.setNegative(false);
95+
extract.filter(*ground_cloud);
96+
97+
extract.setNegative(true);
98+
extract.filter(*obstacle_cloud);
99+
}
100+
101+
// Convert obstacle cloud to ROS message
102+
{
103+
PointCloud2 obstacle_cloud_msg;
104+
pcl::toROSMsg(*obstacle_cloud, obstacle_cloud_msg);
105+
obstacle_cloud_msg.header = input_transformed->header;
106+
output = obstacle_cloud_msg;
107+
}
108+
109+
return true;
110+
}
111+
} // namespace ground_segmentation::ransac_ground_filter
112+
113+
#include "rclcpp_components/register_node_macro.hpp"
114+
RCLCPP_COMPONENTS_REGISTER_NODE(ground_segmentation::ransac_ground_filter::RANSACGroundFilter)

0 commit comments

Comments
 (0)