Author: Jordi Pages <jordi.pages@pal-robotics.com>

Maintainer: Jordi Pages <jordi.pages@pal-robotics.com>

Support: tiago-support@pal-robotics.com

Source: https://github.com/pal-robotics/tiago_tutorials.git

(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Cylinder detector (C++)

Description: Cylindrical object detection based on sample consensus segmentation.

Tutorial Level: INTERMEDIATE

Next Tutorial: Region Segmentation

cylinder_detector_title.jpg

Purpose

This example shows how to apply a sample consensus based segmentation algorithm from PCL in order to detect cylindrical objects in point clouds.

Pre-Requisites

First, make sure that the tutorials are properly installed along with the TIAGo simulation, as shown in the Tutorials Installation Section. This example makes use of the table segmentation node presented in the previous tutorial in order to apply the cylinder detector only to those points lying on top of the table.

Execution

Open three consoles and in each one source the workspace

  • cd ~/tiago_public_ws
    source ./devel/setup.bash

Simulation

In the first console launch the simulation

  • roslaunch tiago_gazebo tiago_gazebo.launch public_sim:=true end_effector:=pal-gripper world:=objects_on_table

TIAGo will be spawn in front of a table with several objects.

gazebo_objects_on_table.jpg

Make the robot look at the table

In the second console load an specific file with motion definitions

  • rosparam load `rospack find tiago_pcl_tutorial`/config/pcl_motions.yaml

Now run a graphical action client interface for melodic:

  • rosrun actionlib axclient.py /play_motion

Or for noetic:

  • rosrun actionlib_tools axclient.py /play_motion

axclient_look_down.jpg

In the GUI that shows up write the following text in the Goal text box

  • motion_name: 'look_down'
    skip_planning: True
    priority: 0

And press the SEND GOAL button. The robot will raise its torso and will lower the head in order to look at the table.

Close the axclient GUI.

Table segmentation

In the second console run now the table segmentation node as follows:

  • roslaunch tiago_pcl_tutorial segment_table.launch show_rviz:=false

Cylinder detector

In the third console launch the following file

  • roslaunch tiago_pcl_tutorial cylinder_detector.launch

Rviz will show up showing three point clouds: the table point cloud, the non-table point cloud and a point cloud in yellow corresponding to the biggest cylinder fitted in the non-table point cloud. The cylindrical primitive best fitting the corresponding point cluster will be shown in cyan. Furthermore, the 3D pose of the reconstructed cylinder will be shown as a frame.

cylinder_detection_rviz.jpg

cylinder_fitted_rviz.jpg

Wiki: Robots/TIAGo/Tutorials/CylinderDetector (last edited 2023-02-24 11:10:13 by thomaspeyrucain)