Overview

The purpose of this tutorial is to introduce you to controlling the robot arm with MoveIt. MoveIt is just one approach for controlling the arm that may be 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.

Concepts

When ARIAC starts, it adds a simulated IIWA14 arm to Gazebo and also starts a joint state controller for the arm that receives trajectory_msgs/JointTrajectory messages on the /ariac/arm/command topic. The GEAR interface tutorial has already shown you that you can control the arm by sending such a joint trajectory to the arm's controller through the command line.

MoveIt is a tool that can be used for generating these trajectories programmatically. It does so by combining information about the robot's current state and the state of the environment around it, and feeding this information to a motion planning algorithm.

We have provided a set of configuration files that can be used by ARIAC participants to use MoveIt to control the arm.

This tutorial and the associated configuration files have been published to provide users a starting point for controlling the arm, they are not officially supported features of the competition. Technical support for controlling the arm with MoveIt is not provided as part of the ARIAC competition support.

Get the ARIAC configuration files

To get the MoveIt configurations specific to the arms used in ARIAC, run the following commands to create a catkin_workspace if you have not already done so:

  • $ mkdir -p ~/ariac_ws/src
    $ cd ~/ariac_ws/src

And then download the code:

  • $ git clone https://github.com/osrf/iiwa_stack

This is a fork of IFL-CAMP's iiwa_stack repository, which provides Moveit support for the IIWA14. We have modified it to add the linear actuator and suction gripper used for ARIAC.

Get the dependencies

The following additional dependencies are required to run MoveIt with ARIAC:

  • $ sudo apt-get install ros-kinetic-moveit-core \
                           ros-kinetic-moveit-kinematics \
                           ros-kinetic-moveit-ros-planning \
                           ros-kinetic-moveit-ros-move-group \
                           ros-kinetic-moveit-planners-ompl \
                           ros-kinetic-moveit-ros-visualization \
                           ros-kinetic-moveit-simple-controller-manager

Build the ARIAC MoveIt packages

Now that you have the appropriate dependencies installed, you can build the necessary packages to run control the arm with MoveIt. If you have followed the ARIAC system setup tutorial, you should already have sourced the ROS setup file. If not, run:

  • $ source /opt/ros/kinetic/setup.bash

Now build the workspace with:

  • $ cd ~/ariac_ws
    $ catkin_make install
    $ source install/setup.bash

Run ARIAC + MoveIt

There is a video equivalent of this tutorial from ARIAC 2017 available at https://vimeo.com/182889047

The first step in being able to control the arm using MoveIt is to start ARIAC with an arm in the environment. You can do this by passing particular competition configuration and user configuration files to the gear.py script, or with the following invocation that uses a sample configuration:

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

This will start the ARIAC environment with a simulated arm that has the aforementioned joint controller running.

Run the following command to launch the MoveIt nodes that enable motion planning:

  • $ roslaunch iiwa_moveit moveit_planning_execution.launch sim:=true  model:=iiwa14 hardware_interface:=EffortJointInterface robot_name:=ariac

In particular, this starts the move_group node that can be used to control the arm.

Interfacing with MoveIt

Using the MoveIt RViz plugin

RViz is a visualization tool that can represent the state of robots, both simulated and real. There is an RViz "plugin" for motion planning with MoveIt which can be used to interactively interface with the move_group. To launch RViz with this plugin, run:

  • $ roslaunch iiwa_moveit moveit_rviz.launch config:=true

This should bring up a visualization like the following, which shows the robot state in grey, an "interactive marker" for moving the end effector around, and the goal position for the robot in orange:

https://bytebucket.org/osrf/ariac/wiki/2017/img/rviz_moveit.png

Select the "Planning" tab in the Motion Planning plugin. Move the end effector using the interactive marker and select "Plan" to get MoveIt to generate a joint trajectory matching that goal position. If all goes well, you should then be able to select "Execute" to send this trajectory to the arm's controller.

You should see that the arm moves in Gazebo, and that this movement is reflected in the visualization in RViz.

If you would like to visualize the TF frames associated with various locations in the environment, in the Displays panel of RViz, click Add > By display type, and under the rviz folder select TF.

Programmatically

We refer you to the MoveIt tutorials page for details on interfacing with MoveIt programmatically.

Troubleshooting

As previously mentioned, this tutorial has been provided as a starting point, it is not an officially supported feature of the competition. The ARIAC competition support team do not provide technical support for using MoveIt to control the arm in the ARIAC environment, but teams are free to modify the configuration files provided if appropriate.

MoveIt is only one possible approach for controlling the arm: teams are free to use alternative motion planning and execution strategies entirely.

Wiki: ariac/2018/Tutorials/MoveItInterface (last edited 2018-03-22 02:07:03 by DHood)