Main Content

Palletize Boxes Using Cobot with Simulink 3D Animation™

Since R2024b

This example shows how to use a cobot to palletize boxes in a Simulink® simulation with Unreal Engine® and Simulation 3D Animation blocks.

The robot motion planning workflow for palletizing in this example closely resembles the workflows in these examples:

This example uses the Universal Robots UR10e and the Robotiq® EPick 4-cup vacuum gripper to pick up boxes from a conveyor belt and stack them in a pallet. To simulate the action of a conveyor belt, the model spawns new boxes at a fixed location.

Cobot placing boxes in arrangement on a pallet.

Set Up Cobot

Load the cobot and the vacuum gripper. Place the cobot on a platform that provides it a good height from which to perform the palletization.

% Setup the rigidBodyTree
rbt = rigidBodyTree(MaxNumBodies=14,DataFormat="row");
rbt.BaseName = 'world';

% Define the base of the robot as a raised platform 
extBase = rigidBody('externalBase','MaxNumCollisions',1);
if(coder.target('MATLAB'))
    addVisual(extBase,"box",[0.25,0.25,0.5],trvec2tform([0,0,-0.25]));
end
addCollision(extBase,collisionBox(0.25,0.25,0.5),trvec2tform([0,0,-0.25]));
extBaseJnt = rigidBodyJoint('externalBaseJoint','fixed');
setFixedTransform(extBaseJnt,trvec2tform([0 0 0.5]));
extBase.Joint = extBaseJnt;

% Add base to the tree
addBody(rbt,extBase,'world')

% Load the robot rigidBodyTree
urrobot = loadrobot("universalUR10e",DataFormat="row");

% Add the robot tree to the base 
addSubtree(rbt,'externalBase',urrobot)

% Load the gripper rigidBodyTree
gripper = loadrobot("robotiqEPick4CupVacuumAssembly", Dataformat="row");

% Add the gripper to the tree
addSubtree(rbt,'tool0',gripper)

Set the dimensions of the boxes, the number of total boxes to be palletized, and the spawning location on the conveyor belt.

boxDim = 0.2;
maxNumOfBoxes = 30;
boxPosition = [-0.65 0.65 0.6];

Model Overview

Open the palletizing simulation model.

open_system("PalletizeBoxesUsingCobot.slx");

Palletizing Simulink model.

The model is organized into three areas:

Scene Creation and Configuration

The warehouse simulation environment is setup with these blocks:

  • Simulink 3D Scene Configuration block, that defines the baseline Unreal Engine™ environment which the model connects to.

  • Actor block named Warehouse World that configures the scene with known assets using the initialization script. This script populates the world with the bench and pallet assets and places the first box on the bench.

Scene creation and configuration area of the palletizing Simulink model.

Read Scene Attributes

The Read Scene Attributes area handles spawning new boxes into the scene and switches the grasping state based on the current state in the palletizing workflow.

Read scene attributes area of the palletizing Simulink model.

When the cobot completes a trajectory, the change in state affects the grasp state of the cobot and spawns a new box depending on the state value:

  • State == -1 — Open gripper and move toward the bench. When the state changes from 1 to -1, the Spawn New Box subsystem spawns a new block on the bench.

  • State == 1 — Close gripper and move toward the pallet with a grasped box. When the cobot places a box on the pallet, the state changes to -1, triggering a new box to spawn on the bench.

Spawn New Box is also a triggered subsystem, but is only triggered on the falling signal when the current box is being released on the pallet. This spawns a new box on the bench and assigns it a new ID number, incrementing the ID by 1 each time.

Trajectory Planning

The Trajectory Planning area generates a trajectory using the Trajectory Planner subsystem and optimizes the trajectory using the contopptraj function.

Trajectory Planner is a triggered subsystem that generates the palletizing trajectory when there is a new box to palletize. It uses manipulatorRRT to plan the motion of the manipulator by first computing the desired start and goal positions of the cobot end effector. This subsystem runs only once at the start of the new motion plan, triggered by the triggerStateChange MATLAB® function block. This image shows the Trajectory Planner subsystem.

Trajectory planner triggered subsystem.

Trajectory Planner Trigger

When triggerStateChange block outputs a value of -1, the cobot is moves toward the bench. When it outputs a value of 1, the robot is moves towards the pallet. The switches flip the start and goal positions depending on the current state in the palletizing workflow.

Boxes Poses

The new boxes appear at a constant pose on the bench. The goal pose for placing new boxes on the pallet changes depending on the available space on the pallet. The getPalletGoalPose function block finds an open space on the pallet and outputs the goal pose for a new box. This block accepts the ID number of a new box, its dimensions from the workspace, and computes the goal pose using a palletizing pattern defined by the exampleHelperPalletArrangement function.

Trajectory Planning

Once the desired start and goal positions of the boxes are known, the Trajectory Planner subsystem applies a translation to the poses to get the desired end-effector positions. Then it uses the inverseKinematics block to calculate the joint configurations with inverse kinematics. Then the helperManipulatorRRT MATLAB function block calculates the desired waypoints. This block also updates the collision environment each time the subsystem is triggered to account for the increasing number of boxes in the environment. The helperContopptraj MATLAB function block then takes the planned waypoints from the planner and outputs a time-optimal, interpolated trajectory for the cobot to use to palletize the new box.

Palletizing Boxes

The model creates the cobot rigidBodyTree in the Unreal Engine® environment using the Simulation 3D Robot block. This block accepts the joint trajectory to grab a new box from the bench and place it on the pallet.

When the current cobot configuration is within a threshold of the desired goal configuration, the stateChange function block changes the output signal value affecting the grasp state and spawns a new box.

Simulate Model

Run the model with the following command

sim("PalletizeBoxesUsingCobot.slx");

GIF of cobot palletizing boxes in an arrangement.

See Also

|

Related Topics

External Websites