ROS package for detecting the middle of the passage between two rows of grapevines.
Point Cloud Library (PCL) is used to detect the border rows from a 3D LiDAR scan.
- Removes pointcloud points inside the Remove Box
- Removes pointcloud points outside the Keep Box
- Flattens the remaining pointcloud (sets the z component to zero)
- Detects all the lines subject to max_angle and min_points parameters
- Selects right and left borders from detected lines
- Calculates the middle line and publishes it to the middle_line topic
This project depends on ROS, PCL and Eigen
Clone into a catkin workspace and build with:
catkin build vineyard_midrow_detection
To launch the node along with Rviz visualization:
roslaunch vineyard_midrow_detection mid_row_detection.launch
-
Line Detection- PCL line detection using RANSACline_detection_distance_threshold- minimum distance for a point to be considered a line inlierline_detection_max_angle- maximum angle of a line to be considered a candidate for border selectionline_detection_min_points- minimum number of points to perform line detection on
-
Keep Box- points inside the Keep Box cuboid are considered for line detectionkeep_box_lower_bound_xkeep_box_upper_bound_xkeep_box_lower_bound_ykeep_box_upper_bound_ykeep_box_lower_bound_zkeep_box_upper_bound_z
-
Remove Box- points inside the Remove Box cuboid are removed. Used to remove irrelevant points such as vehicle partsremove_box_lower_bound_xremove_box_upper_bound_xremove_box_lower_bound_yremove_box_upper_bound_yremove_box_lower_bound_zremove_box_upper_bound_z
rviz- start RVIZ (default true)rqt_reconfigure- start rqt_reconfigure (default true)ros_rate- ros rate (default 50Hz)input_pointcloud_topic- Pointcloud2 topic (default /rslidar_points)
