Shutter MoveIt Config Package

Follow these instructions to install MoveIt for Noetic. Note that to create this package, we had to build MoveIt from source because when it was created, the tutorial recommended this procedure for Noetic.

This package was generated by following the steps in the MoveIt Setup Assistant tutorial.

Package Structure

This package primarily consolidates the configuration and launch files for using the MoveIt planning framework with Shutter. The following sections point to the most important files that will probably be referenced by higher-level launch files that use MoveIt. For an example of a package-specific launch file, see shutter_teleop/launch/shutter_controller.launch.

Configuration Files

  • kinematics.yaml: parameters for the KDL inverse kinematics solver. Other IK solver configurations are specified in the files with naming convention <solver>_kinematics.yaml.

  • chomp_planning.yaml: parameters for CHOMP motion planner.

  • ompl_planning.yaml: parameters for the planners implemented by the Open Motion Planning Library.

  • ros_controllers.yaml: parameters for the controllers accessed with ROS Control. These parameters should mirror the ones specified in the shutter_hardware_interface package.

Launch Files

The first set of launch files are needed for any higher-level interface to MoveIt:

  • planning_context.launch: loads the robot description, joint limits and inverse kinematics settings.

  • trajectory_execution.launch.xml: starts the controller manager and trajectory execution manager.

  • <chomp|ompl>_planning_pipeline.launch.xml: loads the planning pipeline for either CHOMP or OMPL motion planners.

The following two launch files comprise complete MoveIt pipelines:

  • demo.launch: runs a demonstration of the RViz Motion Planning plugin for a fake, simulated or physical robot. This launch file is described in greater detail in the next section.

  • python_interface_tutorial.launch: runs a demonstration of the Move Group Python interface.

Getting Started

To test out MoveIt with Shutter, run:

$ roslaunch shutter_moveit_config demo.launch moveit_controller_manager:=[fake | simple | ros_control]

Different values for moveit_controller_manager allow control of different robot setups:

  • fake runs the robot entirely in RViz simulation

  • simple runs the robot in a standalone simulation built with the Unity game engine.

  • ros_control runs the physical robot (if attached)

If no controller manager is specified, the argument defaults to fake.

This basic usage of demo.launch is useful to validate the MoveIt installation, planners and IK solvers.

Common Arguments to demo.launch

  • ik_solver: the inverse kinematics solver used by MoveIt. The recommendation for Shutter is bio_ik, though MoveIt itself generally defaults to kdl. Other solvers are specified in config/<solver_name>_kinematics.yaml

  • pipeline: the planning pipeline for MoveIt. The default is chomp. Note that this pipeline can be changed in the “Motion Planning > Context” menu in RViz.

Controlling Shutter in RViz

Once MoveIt has been started, new goal poses can be specified for Shutter with the six colored handles in RViz. The handles specify translations and rotations in the head_link frame (RGB corresponds to XYZ, respectively). Because Shutter only has four degrees of freedom, not all of the handles have an effect. Alternatively, a goal pose can be specified by dragging the blue orb centered on the origin of the head_link frame.

Once the goal pose is set, MoveIt will plan and execute the trajectory upon clicking the “Plan and Execute” button.

The animation below illustrates a few plan-and-execute cycles in RViz.

controlling Shutter with MoveIt in RViz