Gazebo Simulation of Semi-Structured Intelligent Bin Picking for UR5e Using YOLO and PCA-Based Object Detection
This example shows detailed workflow for simulating intelligent bin picking using Universal Robots UR5e cobot in Gazebo. The MATLAB project provided with this example consists of the Initialize, DataGeneration, Perception, Motion Planning, and Integration modules (project folders) to create a complete bin picking workflow.
Open the Project
To get started, open the example live script and access the supporting files by either clicking Open Live Script in the documentation or using the openExample
function.
openExample('urseries/GazeboSimulationSemiStructuredIntelligentBinPickingUR5eExample');
Then, open the Simulink™ project file.
prj = openProject('BinPickingUR5eSimulation/BinPickingGazeboSimExampleProject.prj');
Bin Picking Workflow
This diagram shows the operations involved in the one complete execution cycle for the simulation of cobot bin picking application.
In this example, we are targeting semi-structured bin picking, which is a classification based on the bin complexity.
On a high level, this task can be divided into two major modules:
Vision processing / Perception module
Motion / Trajectory planning module
Vision Processing or Perception module
This workflow can be further divided into two areas:
Object detection using RGB data, which is object segmentation based on RGB and depth (RGBD) data using deep learning
Object pose estimation using 3D point cloud data, which can be used to estimate the pose of the identified object for motion planning
This diagram shows the steps involved in the object pose estimation using YOLOv4 and PCA-based algorithm.
The perception process involves two main steps,
Training and validation: Training of the RGB based object detection network (YOLOv4) and its validation against the test dataset.
Online object detection: Pose estimation using realtime raw RGBD data using pre-trained YOLOv4 network and Principle Component Analysis (PCA).
Motion Planning Module
This workflow can be divided into two areas:
Smart motion planning, which picks the logic for motion planning from the detected parts
Goal execution, which executes trajectory planning for pick and place operation using UR5e cobot
The planner entry point function is designed from the algorithm used in Motion Planning and RigidBodyTree Simulation of UR5e for Bin Picking Using manipulatorRRT Algorithm example. This algorithm uses manipulatorRRT
plan an approach, and pick and place trajectories in the collision environment.
Generating a MEX function using C/C++ code generation helps you to reduce the computation time, thereby reducing the pick and place cycle time.
For more information on MEX function creation for the manipulatorRRT algorithm-based planner, refer to Generate Code for Manipulator Motion Planning in Perceived Environment example.
Also, refer to this example to know more about how to generate MEX function to accelerate your MATLAB program execution.
Required Software
This example requires:
MATLAB
Robotics System Toolbox
Computer Vision Toolbox
Deep Learning Toolbox
Image Processing Toolbox
ROS Toolbox
Optimization Toolbox
Statistics and Machine Learning Toolbox
MATLAB Coder (Required if you want to use MEX function for motion planner)
Robotics System Toolbox Support Package for Universal Robots UR Series Manipulators
Computer Vision Toolbox Model for YOLO v4 Object Detection support package (Required if you want to train a detector model)
This example requires downloading a virtual machine to use the pre-configured Gazebo environment. Follow the below section for more information.
Download ROS Virtual Machine For Pre-Installed Gazebo Environment
You can download a virtual machine image that already has ROS and Gazebo installed. This virtual machine is based on Ubuntu® Linux® and is pre-configured to support the examples in ROS Toolbox™.
Refer to Get Started with Gazebo and Simulated TurtleBot. Download and install the ROS virtual machine from the link given under "Download Virtual Machine" section of the page.
Launch the virtual machine.
Plugins and ROS drivers used in this simulation example
Simulated Universal Robots UR5e
Simulated Robotiq Epick suction gripper
Simulated Intel® RealSense™ Depth Camera D415
Interface used for Universal Robots UR5e
The functionality from Robotics System Toolbox Support Package for Universal Robots UR Series Manipulators is used for trajectory and joint control of the simulated Universal Robots UR5e. This support package offers urROSNode
object
to enable control over the ROS interface.
Interface used for Robotiq Epick Suction Gripper
To simulate a virtual suction gripper, we use custom modified vacuum gripper plugin of the ROS gazebo_plugin. The plugin is modified in such a way that it creates a virtual joint between the end-effector body and the target object with some offset distance to attach the object. In this process, it also removes the collision of the object so that it does not have an issue with collisions of the bin or other parts.
For the activation and deactivation of the plugin, activateVacuum
and deactivateVaccum
functions are used which call the respective ROS service.
Interface used for Intel® RealSense™ D415
For perception purposes, Intel® RealSense™ D415 camera depth module is used in this application development. The MATLAB connection is established over the ROS using the IntelRealSense ROS driver. Along with these ROS drivers, realsense_gazebo_plugin is also used for the Gazebo sensor of the D415 sensor.
The dataset used for the training of the YOLOv4 deep learning network has been created using this sensor.
Note: All the plugins and the modifications are included in the downloaded VM with the required license file attached.
Physical Setup for Simulation Used in this Example
For the demonstration of the intelligent bin picking workflow using the Universal Robots UR5e, this example uses a cuboid shape object and a rectangular bin.
Dimensions of the cuboid and bin are provided in the initializeParametersForBinPickingSimulation.m
script.
RigidBodyTree and Actual Environment setup
In this example, we will create a RigidBodyTree environment for motion planning.
This flow chart guides you through the scripts available for the Perception, Motion planning, and Integration modules.
Parameter Initialization
The initialization scripts initializeParametersForBinPickingSimulation.m
runs automatically when you open this MATLAB project. This script defines some of the important parameters used in the perception, motion planning, and integration project module. You can find this script inside the Initialize folder or you can run the below-given command to open the script. Change the parameters if you are running with some different setups accordingly.
open("initializeParametersForBinPickingSimulation.m");
Open Synthetic Data Generation Module Script
Run this command to open the script to generate synthetic data using the Gazebo simulation environment.
open("DatasetGenerationUsingGazeboExample.mlx");
Open Perception Module Script
Download the pre-trained YOLO v4 network and dataset
You need to download the dataset and pre-trained network from this link. We have used pre-trained network in this script for showing the perception pipeline.
Note: Downloading the content from this link is necessary to run this example as it includes the pre-tranined network and dataset for training the network.
Run this command to open the script of the perception workflow. This script covers the full perception pipeline from training to the object pose estimation workflow.
open("DetectionAndPoseEstimationforCuboidSim.mlx");
Note: This script below demonstrates how to train a YOLOv4 object detector for identifying simulated cuboid objects.
open("trainYoloV4ForCuboidObject.mlx");
Open Motion Planning Module Script
Run this command to open the script for the motion planning workflow. This script covers the RigidBodyTree simulation workflow and MEX function generation steps for the motion planning module.
open("BinPickingMotionPlanningMEXGenerationSim.mlx");
Open Integration script
Run this command to open the main script of the integrated workflow. This script shows how to use perception and motion planning modules for creating a full bin-picking application workflow using the simulated Universal Robots UR5e.
open("UR5eSimulationBinPickingApplicationIntegratedScript.mlx");