The move_group node

The figure below shows the high-level system architecture for a key node provided by MoveIt called move_group. This node serves as an integrator: pulling all the individual components together to provide a set of ROS actions and services for users to use.

../../_images/move_group.png

User Interface

The users can access the actions and services provided by move_group in two ways:

Configuration

move_group is a ROS node. It uses the ROS param server to get three kinds of information:

  1. URDF

    • move_group looks for the robot_description parameter to get the URDF for the robot.

  2. SRDF

    • move_group looks for the robot_description_semantic parameter to get the SRDF for the robot. The SRDF is typically created (once) by a user using the MoveIt Setup Assistant.

  3. MoveIt configuration

    • move_group will look for other configuration specific to MoveIt including joint limits, kinematics, motion planning, perception and other information. Config files for these components are automatically generated by the MoveIt Setup Assistant and stored in the config directory of the corresponding MoveIt config package for the robot.

Robot Interface

move_group talks to the robot through ROS topics and actions. It communicates with the robot to get current state information (positions of the joints, etc.), to get point clouds and other sensor data from the robot sensors and to talk to the controllers on the robot.

Joint State Information

move_group listens on the /joint_states topic for determining the current state information - i.e. determining where each joint of the robot is. move_group is capable of listening to multiple publishers on this topic even if they are publishing only partial information about the robot state (e.g. separate publishers may be used for the arm and mobile base of a robot). Note that move_group will not set up its own joint state publisher - this is something that has to be implemented on each robot.

Transform Information

move_group monitors transform information using the ROS TF library. This allows the node to get global information about the pose of the robot (among other things). For instance, the ROS navigation stack will publish the transform between the map frame and base frame of the robot to TF. move_group can use TF to figure out this transform for internal use. Note that move_group only listens to TF. To publish TF information from your robot, you will need to have a robot_state_publisher node running on your robot.

Controller Interface

move_group talks to the controllers on the robot using the FollowJointTrajectoryAction interface. This is a ROS action interface. A server on the robot needs to service this action - this server is not provided by move_group itself. move_group will only instantiate a client to talk to this controller action server on your robot.

Planning Scene

move_group uses the Planning Scene Monitor to maintain a planning scene, which is a representation of the world and the current state of the robot. The robot state can include any objects attached to (carried by) the robot which are considered to be rigidly attached to the robot. More details on the architecture for maintaining and updating the planning scene are outlined in the Planning Scene section below.

Extensible Capabilities

move_group is structured to be easily extensible. Individual capabilities like pick and place, kinematics, motion planning are actually implemented as separate plugins with a common base class. The plugins are configurable using ROS through a set of ROS yaml parameters and through the use of the ROS pluginlib library. Most users will not have to configure move_group plugins since they come automatically configured in the launch files generated by the MoveIt Setup Assistant.