This package provides tree detection on pointcloud data. In particular, it is designed for detecting tree trunks which could later be used for tree grabbing and harvesting. It does not provide the full tree segmentation with the crown. The package was developed in the scope of [1] (see below).
The functionality was developed for an autonomous harvester where the goal is to detect trees in a local map. Nonetheless, it can also be used on large maps to compute tree coordinates or get an estimate of tree density.
Released under BSD 3-Clause license.
Author: Edo Jelavic
Maintainer: Edo Jelavic, [email protected]
Examples of tree detection on point clouds:
forest 2 (ground removed) | forest 3 | forest 4 |
---|---|---|
The code for tree detection has been developed as a part of research on autonomous precision harvesting. If you are using this tree detector in academic context, please consider adding the following citation to your publication:
[1] Jelavic, E., Jud, D., Egli, P. and Hutter, M., 2021. Towards Autonomous Robotic Precision Harvesting: Mapping, Localization, Planning and Control for a Legged Tree Harvester.
@article{jelavic2021towards,
title={Towards Autonomous Robotic Precision Harvesting: Mapping, Localization, Planning and Control for a Legged Tree Harvester},
author={Jelavic, Edo and Jud, Dominic and Egli, Pascal and Hutter, Marco},
journal={Field Robotics},
year={2021},
publisher={Wiley}
}
This repository consists of following packages:
- point_cloud_preprocessig is a package used to preprocess the point cloud before removing the ground plane
- ground_plane_removal is a lightweight package for ground plane removal.
- tree_detection implements the core algorithm for tree detection.
- tree_detection_ros adds visualization and I/O handling for easier usage. This package is tightly integrated with ROS.
The algorithm first attempts to remove the gound plane. This can be done using two strategies, either a simple box filter (for which the user needs to provide the cropping region) or using an elevation map. In case the elevation map strategy is used, the algorithm first computes the elevation map and then uses it to remove the ground plane. The elevaiton map computation is implemented in a different package (see the link here) and a more detailed description can be found in [1]. Before proceeding with the pointcloud processing the median filter is applied to the elevation map.
Once the ground plane is removed, the algorithm proceeds with Euclidean cluster extraction and performs some checks to make sure that the extracted clusters aree indeed trees. The more detailed description can be found in [1].
Clone the following dependencies:
# in your source folder `src`
git clone https://github.com/ANYbotics/grid_map.git
Installing the grid map from apt might not work (you'll get compiler errors). Recommended way is to build the grid map from source.
Install the ROS and library dependencies with:
sudo apt install -y ros-noetic-pcl-ros ros-noetic-pcl-conversions ros-noetic-jsk-recognition-msgs ros-noetic-tf2-geometry-msgs
# OR, use rosdep in your source folder `src`
sudo rosdep install -yr --from-paths .
In case you want to use the detection boxes for visualization you will have to install the jsk_rviz_plugins.
sudo apt install ros-noetic-jsk-visualization
Recommended to build in release mode for performance (catkin config -DCMAKE_BUILD_TYPE=Release
)
Build with:
catkin build tree_detection_ros
In case you want to visualize the elevation map created by the ground plane remover, you should compile the grid_map_rviz_plugin as well:
catkin build grid_map_rviz_plugin
The example datasets can be downloaded here. The folder contains five forest patches. One dataset has almost no clutter (forest3.pcd) and two have a lot of branch clutter (forest1.pcd and forest2.pcd).
This package can also work with forests on inclined surfaces and we provide two examples (forest4.pcd and forest5.pcd). The point clouds forest4.pcd and forest5.pcd were taken from the The Montmorency dataset and downsampled. Note that for these datasets, we recommend to use a slightly different tuning. See tree_detection_dataset_4_and_5.yaml
.
Modify the pcd_filepath
inside the tree_detection.launch
to point the location where the point clouds .pcd
files are stored.
If you want to use a different configuraiton file, you will have to modify the config_filepath
as well. The ground plane removal strategy can be selected by setting the value of ground_removal_strategy
parameter.
Run with:
roslaunch tree_detection_ros tree_detection.launch
The node publishes the input pointcloud, the pointcloud with the ground removed and the elevation map used to remove the ground plane. The detected trees will be marked with green cylinders and bounding boxes. The visualization should appar in the Rviz window.
Note that the computation can last for up to 7-9 minutes for larger datasets (e.g. forest4.pcd and forest5.pcd). This can be shortened with different tuning, downsampling or voxelizing the point clouds.
If the choice is made to use the point cloud preprocessing package, special care needs to be taken that the voxel grid leaf size is chosen big enough. (Otherwise, there is an integer overflow in the pcl library and a warning is popping up in the terminal.) In addition, if the ground plane is removed using the elevation map approach, it is important, that the crop box of the preprocessing is not removing partially the point cloud representing the ground plane, else the elevation map will not correctly be generated. This could result to the fact that trees are not detected in the point cloud.
In general, the preprocessing should only be applied to point clouds, which either have points far away from the origin and/or which are dense. Both phemomena decrease the processing speed of the tree detection significally! The first phenomenum can be handled using the crop box in the preprocessing package. The second one can be tackled using the voxel grid filter in the same package.
ground_plane_removal/cropbox
- Limits (XYZ) for the ground plane removal. The points contained within the box specified by the user will be kept and the rest will be removed. The tree detection will proceed on the remaining points.ground_plane_removal/elevation_map
- Parameters for elevation map extraction from the pointcloud are described here. We add a couple of new parameters which are listed below.ground_plane_removal/min_height_above_ground
- minimal height above the extracted elevation map to keep the points. Any points below this threshold will be discarded. Note that this number can also be negative.ground_plane_removal/max_height_above_ground
- maximal height above the elevation map to keep the points. Any points above this threshold will be discarded.ground_plane_removal/is_use_median_filter
- whether to apply the median filter on the elevation map.ground_plane_removal/median_filtering_radius
- median filtering radius for the elevation map. For each cell, the filter will take the data from the neighbouring cells withing specified radius and apply the median filter. The number of neighbouring points depends on the cell size and this parameter.ground_plane_removal/median_filter_points_downsample_factor
- If one wishes to have sparser coverage, you can apply downsampling. The algorithm will calculate all the points within the specified radius and divide their number by this factor. E.g., (if there are 50 neighbouring points within the radius and the downsample factor is set to 5, 10 points will be used for median filtering).