Contents
Overview
The purpose of this tutorial is to introduce you to the competition interface that is used to interact with GEAR, the software used by teams participating in the Agile Robotics for Industrial Automation Competition (ARIAC).
Note: this tutorial assumes you are using ROS Kinetic (Ubuntu Xenial 16.04), the officially supported ROS distro for ARIAC 2018.
GEAR provides a ROS interface to the teams for controlling all available actuators, reading sensor information and sending/receiving notifications. We highly recommend going through the Tutorials to get familiar with ROS, in particular, ROS topics and services.
This tutorial will only use command-line interfaces to GEAR; see the Hello World tutorial for an example of how to programmatically interface with GEAR.
Running GEAR
After following the System Setup tutorial, you should have GEAR installed. To setup your terminal for running GEAR, you will have to run:
$ source /opt/ros/kinetic/setup.bash
and, if you installed GEAR from source, you will also have to source the relevant setup file from the GEAR install, such as:
$ source ~/ariac_ws/install/setup.bash
This will have to be done for each new terminal opened: we recommend adding it to your bash.rc.
To launch GEAR with a sample work cell environment configuration that contains a IIWA14 arm and some sensors in various locations, run:
$ roslaunch osrf_gear sample_environment.launch
Use this invocation for the rest of the tutorial so that we have some components to interact with: it should start Gazebo and all of the competition handling code.
Note: Previous versions of GEAR used the UR10, which is still used in some tutorial images.
Starting the competition
When GEAR is started, the various competition elements will be in an inactive state. You need to call a service to start the competition. After launching GEAR, you can execute the following command in a new terminal to manually start the competition:
$ rosservice call /ariac/start_competition
You should see a message that the competition was successfully started.
Receiving orders
As described in the competition specifications, an order is composed of a set of shipments to prepare. Orders are communicated to the teams via ROS messages on the topic /ariac/orders. Teams should subscribe to this topic to receive the initial order, as well as any future order updates. To see the last order that was published, once the competition has been started, run:
$ rostopic echo /ariac/orders
You should observe the initial order expected to be completed.
You must use sensors to detect and classify the products in the storage unit in order to choose the required products for the order. This is covered in the next tutorial.
Controlling the vacuum gripper
Each arm has a simulated pneumatic gripper attached to the arm's end effector. Teams can enable or disable the suction of the gripper. When the suction is enabled and the gripper is making contact with a product, the contacting product will be attached to the gripper. At any point, teams will also be able to disable the suction, causing the detachment of the object if it was previously attached. To enable the gripper's suction from the command line, run:
$ rosservice call /ariac/gripper/control "enable: true"
The gripper periodically publishes its internal state on topic /ariac/gripper/state. If you subscribe to this topic, you'll be able to introspect the gripper's status. In particular, you can check whether the suction is enabled/disabled or whether there is an object attached to the gripper. Execute the following command to display the gripper's state using the console:
$ rostopic echo /ariac/gripper/state -n 1 enabled: True attached: False ---
We will demonstrate the use of the suction gripper to transport a product in the following section. You can disable the suction again for now with:
$ rosservice call /ariac/gripper/control "enable: false"
Controlling the arm
The IIWA14 simulation and control code is provided by IFL-CAMP's iiwa_stack ROS packages. The control parameters have been modified for use in the ARIAC simulation.
The arm's controller is subscribed to the /ariac/arm/command topic and so that topic can be used to control all the joints of the arm. This topic uses the trajectory_msgs/JointTrajectory message type for specifying the desired position, velocity, acceleration and/or effort for each joint. The arm's controller will try to match the commanded states.
Note that some combinations of goal types will not work. We recommend using just position for goals, but others are possible. The arm is controlled by an instance of the ros_controllers/joint_trajectory_controller, see the documentation of that package for more details:
http://wiki.ros.org/joint_trajectory_controller
Command-line
Note that the following sequence of commands should be executed without much delay between the commands, or they may not work as expected.
As an example of controlling the arm from the command-line, starting with the arm over the bins, to move the arm call:
$ rostopic pub /ariac/arm/command trajectory_msgs/JointTrajectory \ "{joint_names: ['iiwa_joint_1', 'iiwa_joint_2', 'iiwa_joint_3', 'iiwa_joint_4', 'iiwa_joint_5', 'iiwa_joint_6', 'iiwa_joint_7', 'linear_arm_actuator_joint'], \ points: [ \ {time_from_start: {secs: 1}, \ positions: [-1.272, -1.102, 0.050, 1.112, -1.329, 1.360, 0.902, -0.663]}, \ {time_from_start: {secs: 3}, \ positions: [0.444, -1.885, -1.726, 1.945, -0.941, 1.754, -2.380, -0.018]}, \ {time_from_start: {secs: 4}, \ positions: [0.025, -1.484, -2.085, 0.046, -1.041, 1.317, -2.134, 0.259]}, \ {time_from_start: {secs: 5}, \ positions: [0.100, -1.751, -2.046, 0.010, -1.11, 1.312, -2.088, 0.190]} \ ]}" -1
You should see that the controller for the arm receives the joint trajectory and moves the arm to the joint positions specified. To verify, run:
$ rostopic echo /ariac/joint_states -n 1
You should see the arm's joints approximately match the requested values.
The /ariac/joint_states topic uses the sensor_msgs/JointState message type, which contains the joint positions, velocities, efforts, and the name of the joints. This is the same type of message that is published when the ROS driver is connected to an actual robot arm as opposed to an arm simulated in Gazebo.
Also, the state of the arm's controller is periodically published on the /ariac/arm/state topic. See the control_msgs/JointTrajectoryControllerState message type for more information. This might be useful for debugging, but it may or may not be available when using an actual robot arm.
Now that the arm is over a product, enable the suction gripper:
$ rosservice call /ariac/gripper/control true
You should see that the gripper is now enabled and has a product:
$ rostopic echo /ariac/gripper/state -n 1 enabled: True attached: True
Shipments from orders are to be built in shipping boxes that move along the belt. For demonstration purposes, in this demo there is a shipping box that starts in front of the arm in the center of the belt. If we want to move the product over the shipping box, it is not sufficient to send a single point to the arm controller, or we will hit obstacles in the environment. Instead, like before, we will send a sequence of points to be reached over the course of a few seconds:
$ rostopic pub /ariac/arm/command trajectory_msgs/JointTrajectory \ "{joint_names: ['iiwa_joint_1', 'iiwa_joint_2', 'iiwa_joint_3', 'iiwa_joint_4', 'iiwa_joint_5', 'iiwa_joint_6', 'iiwa_joint_7', 'linear_arm_actuator_joint'], \ points: [ \ {time_from_start: {secs: 1}, \ positions: [0.216, -1.672, -2.10, 0.584, -1.140, 1.574, -2.380, 0.150]}, \ {time_from_start: {secs: 3}, \ positions: [0.678, -2.060, -2.031, 1.876, -1.107, 1.914, -3.020, 0.294]}, \ {time_from_start: {secs: 4}, \ positions: [1.601, -1.893, -2.465, 0.800, -0.893, 1.919, -2.572, 0.887]}, \ {time_from_start: {secs: 5}, \ positions: [2.795, -2.009, -2.316, 0.556, -0.746, 1.745, -1.215, 0.206]} \ ]}" -1
With the arm now over a shipping box, we drop the product by disabling the suction gripper:
$ rosservice call /ariac/gripper/control false
We will see how to submit shipping boxes for delivery in the following section.
rqt GUI
To control the arm from a GUI, run:
$ rqt
Open a joint controller with Plugins > Robot tools > Joint trajectory controller. Select the ariac/arm controller on the /controller_manager namespace and push the power button to enable the controller. You should be able to adjust the arm position by modifying the 7 joint values (enlarge the window if you cannot see 7 joints).
Be aware that enabling the joint trajectory controller in rqt can conflict with other joint trajectories that the arm might be receiving from, for example, the command-line. Disable the controller in rqt if you wish to send trajectories from the command-line.
MoveIt
See the MoveIt tutorial for an example of using MoveIt to control the arm.
Controlling the conveyor belt
The service /ariac/conveyor/control can be used to modify the power of the conveyor belt or stop it. The power can be 0 or a value in the range of 50 to 100, with 100 representing full speed.
You can start the conveyor belt with:
$ rosservice call /ariac/conveyor/control "power: 100"
Delivering shipping boxes: drone communication
When contestants have completed a shipment, they must wait for it to be in the drone pickup area at the end of the belt, at which point they can notify a drone to deliver the box. The ROS service /ariac/drone is used for this purpose. You must specify the name of the delivery that is in the box, which is communicated in the order.
Assuming you have followed the steps above to move a product into the shipping box and start the conveyor belt, once the box reaches the drone collection area, trigger the drone with:
$ rosservice call /ariac/drone "shipment_type: order_0_shipment_0"
You should see the drone collect the box and an output on the terminal running ARIAC with the score of the shipment.
If multiple shipments need to be delivered, the drone can be called to collect another shipment once the first one has been delivered.
Drone collection area congestion
If a shipping box reaches the end of the conveyor belt while there is already one waiting to be collected, the conveyor belt will be stopped to avoid congestion of the drone collection area. Control of the conveyor belt will be disabled until the waiting box is collected. At that point the belt control will be re-enabled and you may restore power to the belt.
To know if the drone collection area is congested, you can check the state of the conveyor belt:
$ rostopic echo /ariac/conveyor/state -n 1 power: 0.0 enabled: False
If the conveyor belt is not enabled, this implies that the collection area is congested. Even when the area is clear again, power will not be restored to the belt automatically so that it does not interfere with in-progress order fulfillment.
Trial end
When all orders have been filled, or the time limit for the trial has been exhausted, the competition state published on /ariac/competition_state will change to done.
Check that this is the case with:
$ rostopic echo /ariac/competition_state -n 1
If you wish to request that the trial end early (e.g. you have detected a fault with your system and wish to terminate early), you can do so with the following command:
$ rosservice call /ariac/end_competition
Faulty products
There are quality control sensors in the environment that publish the pose of faulty products that they detect in shipping boxes. The following characteristics apply to quality control sensors:
- They are positioned above the conveyor belt in fixed locations: users cannot specify the locations of these sensors.
- They report only the presence of faulty products: they do not report any information about non-faulty products.
- They will only detect faulty products once they are in the shipping boxes.
They are of similar appearance and have an equivalent interface to the logical camera sensors, but they report "anonymized" model names.
Close the previous simulation and start the following demonstration environment instead:
$ roslaunch osrf_gear sample_environment.launch fill_demo_shipment:=true
Start the competition which will cause a shipping box to be filled with a demonstration of the requested shipment:
$ rosservice call /ariac/start_competition
Check the output of the quality control sensor above the shipping box:
$ rostopic echo /ariac/quality_control_sensor_1 -n 1
You should see that one of the products in the shipping box has been detected as faulty by the sensor, but the other product on the tray passes quality control and is not reported:
models: - type: "model" pose: position: x: 0.751716205749 y: 0.0600043173288 z: 0.0985232366527 orientation: x: -0.501587004983 y: -0.497356499713 z: 0.49937685368 w: 0.501666967853 pose: position: x: 1.2 y: 1.0 z: 1.2 orientation: x: 0.500001834279 y: 0.499998161074 z: -0.50004999982 w: 0.49994999982
The quality control sensors also publish TF frames of the faulty products detected. See the logical camera tutorial for more details.
TF frames
GEAR publishes various TF frames of various poses in the world. These frames may be useful when developing the robot control algorithm. To visualize the TF frames in rviz for example, install rviz if you don't already have it, and run:
$ rosrun rviz rviz -d `catkin_find osrf_gear --share --first-only`/rviz/ariac.rviz
For more information on working with TF frames see the tf2 tutorials.
Note that GEAR uses tf2_msgs and not the deprecated tf_msgs. Accordingly, you should use the tf2 package instead of tf.
Troubleshooting interfaces
There are a few interfaces that will not be available during the competition but can be useful during development. See the developer tips page for details on how to enable cheats.
Viewing shipping box contents
The /ariac/shipping_boxes topic can be used during development for seeing the pose of products in the shipping boxes in the same frame as that which will be used for shipment evaluation.
For example, you can see the reported poses of the contents of the shipping box that was filled earlier in the tutorial:
$ rostopic echo /ariac/shipping_boxes shipping_box: "shipping_box_0::box_base" products: - type: "piston_rod_part" is_faulty: True pose: position: x: 0.0999989652909 y: -0.100000011402 z: 0.00204293227133 orientation: x: -2.05060400345e-05 y: -0.000236865642066 z: 5.70695519442e-08 w: 0.999999971737 - type: "gear_part" is_faulty: False pose: position: x: -0.100000006676 y: -5.09799054083e-08 z: 0.00212649637222 orientation: x: 2.1792494845e-07 y: -1.32808898645e-05 z: 0.999999999912 w: -2.02995197141e-08 - type: "gear_part" is_faulty: False pose: position: x: -0.099999993586 y: 0.14999989976 z: 0.00213088917072 orientation: x: 2.35844845602e-05 y: 4.41259103785e-06 z: 1.20229498212e-08 w: 0.999999999712 ---
Submitting shipping boxes without drone delivery
The /ariac/submit_shipment service can be used during development for submitting shipping boxes for evaluation without them being ready for drone collection.
For example, once the competition has been started:
$ rosservice call /ariac/submit_shipment "shipping_box_id: 'shipping_box_0::box_base' shipment_type: 'order_0_shipment_0'" success: True inspection_result: 4.0
Querying storage locations of products
To determine where in the workcell products may be found, you can use the osrf_gear/GetMaterialLocations service. The storage units where products are found will change between trials. An example service call and response is:
$ rosservice call /ariac/material_locations "material_type: piston_rod_part" storage_units: - unit_id: bin2
which suggests that products of type piston_rod_part may be found in bin2. The TF frame bin2_frame can be used to know the location of bin2 with respect to the origin of the "world":
$ rosrun tf tf_echo /world /bin2_frame At time 0.000 - Translation: [-0.850, 0.320, 0.960] - Rotation: in Quaternion [0.125, -0.000, 0.992, 0.000] in RPY (radian) [0.000, -0.250, 3.142] in RPY (degree) [0.000, -14.324, 180.000]
Next steps
Now that you are familiar with the interface to the ARIAC competition, see the sensor interface tutorial to learn how to interface with the available sensors.