@@ -4,13 +4,15 @@ IRI package created to calculate the normal vector of each pointcloud's point in
## Getting Started
The main idea is to calculate the normal vector of each point using it and its closest neighbours. After that, if that vector is out of some thresholds (relative to the inclination with respect to the plane of each point), that point is classified as not passable and, therefore, as an obstacle. On the other hand, if the vector fulfills all the thresholds, it corresponds to a passable terrain.
The main idea is to calculate the normal vector of each point using it and its closest neighbours and fitting the best plane to each group of point-neighbours. After that, if that vector is out of some thresholds (relative to the inclination with respect to the plane of each point), that point is classified as not passable and, therefore, as an obstacle. On the other hand, if the vector fulfills all the thresholds, it corresponds to a passable terrain.
These instructions will get you a copy of the project up and running on your local machine for development and testing purposes.
### Prerequisites
This package is part of the *3d_navigation* project, so you need to install all the necessary packages in the project to see it running.
This package is part of the *3d_navigation* project, so you need to install all the necessary packages in the project to see it running. If you do not care about detecting holes, you can avoid installing the hole detection part of the project.
More specifically, this hole detector works after using a filtering chain aplied to the original pointcloud generated by the camera. This means that you need the package *iri_3dnav* for launchers and the packages *average_point_cloud* and *pcl* for voxel dodwnsampling and several outliers filters.
In addition, for compilation, several packages are necessary: *iri_base_algorithm*, *sensor_msgs*, *pcl_ros*, and *iriutils*.
### Installing
...
...
@@ -28,10 +30,21 @@ cd ..
catkin_make
```
## Params
## Node inputs, outputs and params
### Subscribers
***input**<sensor_msgs::PointCloud2> - It receives a pointcloud (typically the output of an outliers filter or any other filtering stage) and it calculates the normal vector to each point.
### Publishers
***all_rg**<sensor_msgs::PointCloud2> - It outputs the same pointcloud as the input but marking each point using colors: blue for a point at a distance lower than the minimum and, therefore, a non-valid point; green for a point with a valid normal vector (passable terrain) and red for a point with a non-valid normal vector (obstacle).
***obstacles**<sensor_msgs::PointCloud> - It generates a pointcloud with only the points marked as red points. This pointcloud is sent to the navigation stack to be aware of the presence of an obstacle at the position of each red point.
### Params
***filter_min_dist** - Min distance threshold for considering a point valid.
***normal_KSearch** - No of neighbours to estimate the surface.
***filter_min_dist** - Minimum distance threshold for considering a point as valid.
***normal_KSearch** - Number of neighbours to estimate the surface.