Show EOL distros: 

Note: this tutorial will ONLY work with ROS indigo or ROS kinetic

Overview

!!! !!! !!!

The ARIAC 2017 competition is complete. If you are interested in competing in an active ARIAC competition you are probably in the wrong place: this page is only available for archival reasons.

!!! !!! !!!

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).

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 http://wiki.ros.org/ROS/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/$ROS_DISTRO/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 an empty work cell environment configuration, run:

  • $ rosrun osrf_gear gear.py

To launch GEAR with a sample work cell environment configuration that contains a UR10 arm and some sensors in various locations, run:

  • $ rosrun osrf_gear gear.py --development-mode -f `catkin_find --share osrf_gear`/config/sample.yaml

This will use the configuration file sample.yaml to generate the files necessary for launching the competition with the specified environment configuration. These generated files will be output in the /tmp/ariac directory and then run. Use this invocation for the rest of the tutorial so that we have some components to interact with. If you want to specify a different output location, use the -o option.

The UR10 simulation and control code is provided by ROS Industrial's universal_robot ROS packages. The control parameters have been modified for use in the ARIAC simulation.

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 starting GEAR, you can execute the following command 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 kits 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.

Querying storage locations of parts

To determine where in the work cell parts may be found, you can use the osrf_gear/GetMaterialLocations service. The storage units where parts 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: bin7
      - 
        unit_id: belt

which suggests that parts of type piston_rod_part may be found in bin7 and on the conveyor belt. The TF frames bin7_frame and belt_frame can be used to know the location of bin7 and the belt, respectively, and the logical camera sensor can report the specific pose of items of type piston_rod_part in the storage unit. See below for more details on TF frames, and see the sensor interface tutorial for more details on the logical camera.

This service can also be used for locating trays.

  • $ rosservice call /ariac/material_locations tray
    storage_units: 
      - 
        unit_id: agv1_load_point
      - 
        unit_id: agv2_load_point

Similarly, the agv{N}_load_point_frame TF frame is published by the simulation and represents the point of the workcell where the AGV can be found, and the logical camera sensor can report the specific pose of trays on top of the AGV.

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 an object, the contacting object 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"

And in a similar way, to disable the suction, run:

  • $ rosservice call /ariac/gripper/control "enable: false" 

We will demonstrate the use of the suction gripper in the following section.

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
    enabled: False
    attached: False
    ---

Controlling the arm

The UR10 simulation and control code is provided by ROS Industrial's universal_robot 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

As an example of controlling the arm from the command-line, starting with the arm over the bins, call:

  • $ rosservice call /ariac/gripper/control false

to disable the gripper, and then to move the arm call:

  • $ rostopic pub /ariac/arm/command trajectory_msgs/JointTrajectory "{joint_names: \
    ['elbow_joint', 'linear_arm_actuator_joint', 'shoulder_lift_joint', 'shoulder_pan_joint', 'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint'], points: \
    [{time_from_start: {secs: 1}, positions: [1.85, 0.35, -0.38, 2.76, 3.67, -1.51, 0.00]} ]}" -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

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 part, enable the suction gripper:

  • $ rosservice call /ariac/gripper/control true

You should see that the gripper is now enabled and has a part:

  • $ rostopic echo /ariac/gripper/state 
    enabled: True
    attached: True

If we want to move the part over AGV, it is not sufficient to send a single point to the arm controller, or we will hit obstacles in the environment. Instead 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: ['elbow_joint', 'linear_arm_actuator_joint', 'shoulder_lift_joint', 'shoulder_pan_joint', 'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint'], points: [ {time_from_start: {secs: 1}, positions: [1.76, 0.28, -1.38, 2.76, 3.27, -1.51, 0.00]}, {time_from_start: {secs: 2}, positions: [1.76, 0.38, -1.38, 1.5, 3.27, -1.51, 0.0]}, {time_from_start: {secs: 3}, positions: [1.76, 2.06, -1.38, 1.5, 3.27, -1.51, 0.0]}, {time_from_start: {secs: 4}, positions: [1.76, 2.06, -0.63, 1.5, 3.27, -1.51, 0.0]}]}" -1

With the arm now over the tray, we drop the part by disabling the suction gripper:

  • $ rosservice call /ariac/gripper/control false

We will see how to submit trays for evaluation 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.

Submitting trays/AGV communication

Kits from orders are to be built on trays which are stored on the automated guided vehicles (AGVs). When contestants have completed a kit, they should notify the relevant AGV to deliver the tray to the delivery area. The ROS service /ariac/agv{N} is used for this purpose, where N is 1 or 2. You must specify the type of kit that is on the tray, which is communicated in the order. As an example, once the simulation is running and the competition has been started, you can test this service from the console with the following commands.

Spawn a model on the tray on AGV1 (this command is for demonstration purposes and is not permitted during the actual competition):

  • $ rosrun gazebo_ros spawn_model -sdf -x 0.0 -y 0.15 -z 0.1 -R 0 -P 0 -Y 0 -file `catkin_find osrf_gear --share`/models/piston_rod_part_ariac/model.sdf -reference_frame agv1::kit_tray_1::kit_tray_1::tray -model piston_rod_part_1

Call the service to submit the tray for evaluation (remember that the competition must have been started before trays can be submitted for evaluation):

  • $ rosservice call /ariac/agv1 "kit_type: order_0_kit_0"

You should see an output on the terminal running ARIAC with the score of the tray.

If multiple trays need to be submitted, the AGV will return an empty tray after the submitted tray has been evaluated.

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

If you wish to request that the trial end early for whatever reason, you can do so with the following command:

  • $ rosservice call /ariac/end_competition

Faulty parts

There are quality control sensors above each AGV that publish the pose of faulty parts that they see on the tray. The following characteristics apply to quality control sensors:

  • They are positioned above each AGV in pre-defined locations: users cannot specify the locations of these sensors.
  • They report only the presence of faulty parts: they do not report any information about non-faulty parts.
  • They will only detect faulty parts once they are in the trays on AGVs.
  • They are of similar appearance and have an equivalent interface to the logical camera sensors.

Spawn a part that is known to be faulty on the tray on AGV2:

  • $ rosrun gazebo_ros spawn_model -sdf -x 0.1 -y 0.1 -z 0.05 -R 0 -P 0 -Y 0 -file `catkin_find osrf_gear --share`/models/piston_rod_part_ariac/model.sdf -reference_frame agv1::kit_tray_1::kit_tray_1::tray -model piston_rod_part_5

Check the output of the quality control sensor above AGV1:

  • $ rostopic echo /ariac/quality_control_sensor_1

You should see that the part the we just spawned has been detected as faulty by the sensor, but any other parts on the tray pass quality control and are not reported:

  • models: 
      - 
        type: piston_rod_part
        pose: 
          position: 
            x: 0.858267794667
            y: -0.10090291371
            z: 0.149158924264
          orientation: 
            x: 0.399591693548
            y: -0.398453680941
            z: -0.585112911695
            w: 0.582412245029
    pose: 
      position: 
        x: 0.3
        y: -3.5
        z: 1.5
      orientation: 
        x: -0.399901562702
        y: 0.398622456606
        z: 0.584534493431
        w: 0.582664829235

The quality control sensors also publish TF frames of the faulty parts 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 view the TF frames, run:

  • $ rosrun rviz rviz -d `catkin_find osrf_gear --share`/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. Similarly, unless otherwise specified, the use of these interfaces is not permitted during the submission of qualification tasks. See the developer tips page for details on how to enable cheats.

Controlling the conveyor belt

For trials where the conveyor belt is used, the service /ariac/conveyor/control can be used to modify the power of the conveyor belt or stop it. The power can be from 0 to 100, with 100 representing full speed. Start Gazebo with the ARIAC environment, open a new terminal and start the competition.

Wait until you see some of the objects moving on the conveyor belt. Then, make the conveyor belt run at half power:

  • $ rosservice call /ariac/conveyor/control "state: {power: 50}"

Note that setting the belt power between 0 and 50 will cause the belt to function incorrectly.

You can stop the conveyor belt with:

  • $ rosservice call /ariac/conveyor/control "state: {power: 0}"

Be aware that if you stop the conveyor belt for debugging purposes, correct behavior once restarted is not guaranteed.

Viewing kit contents

The /ariac/trays topic can be used during development for seeing the pose of parts on the trays in the same frame as that which will be used for kit evaluation.

For example, spawn a part on a tray:

  • $ rosrun gazebo_ros spawn_model -sdf -x 0.0 -y 0.15 -z 0.1 -R 0 -P 0 -Y 0 -file `catkin_find osrf_gear --share`/models/disk_part_ariac/model.sdf -reference_frame agv2::kit_tray_2::kit_tray_2::tray -model disk_part_0

And now see the reported part poses on the trays:

  • $ rostopic echo /ariac/trays
    tray: agv1::kit_tray_1::kit_tray_1::tray
    kit: 
      kit_type: ''
      objects: []
    ---
    tray: agv2::kit_tray_2::kit_tray_2::tray
    kit: 
      kit_type: ''
      objects: 
        - 
          type: disk_part
          is_faulty: False
          pose: 
            position: 
              x: 3.36714533056e-06
              y: 0.149990455798
              z: 0.00500943062197
            orientation: 
              x: -7.47894669718e-05
              y: 7.88877219651e-06
              z: -7.9694166157e-05
              w: 0.999999993997
    ---

Submitting trays without AGV movement

The /ariac/submit_tray service can be used during development for submitting kit trays for evaluation without having the AGV deliver the tray.

For example, once the competition has been started:

  • $ rosservice call /ariac/submit_tray "tray_id: 'agv2::kit_tray_2::kit_tray_2::tray'
    kit_type: 'order_0_kit_0'" 
    success: True
    inspection_result: 1.0

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.

Wiki: ariac/Tutorials/GEARInterface (last edited 2018-02-18 02:27:12 by DHood)