Skip to content

Commit

Permalink
Update low_level_controllers for ROS2 (moveit#287)
Browse files Browse the repository at this point in the history
  • Loading branch information
AndyZe authored Jan 15, 2022
1 parent 99df38e commit c9b8068
Showing 1 changed file with 37 additions and 97 deletions.
Original file line number Diff line number Diff line change
@@ -1,53 +1,35 @@
:moveit1:

..
Once updated for MoveIt 2, remove all lines above title (including this comment and :moveit1: tag)
Low Level Controllers
=====================
MoveIt has access to many different controllers through a plugin interface inside the `MoveItControllerHandler <https://github.com/ros-planning/moveit/tree/master/moveit_plugins/moveit_ros_control_interface>`_ class. The MoveItControllerManager class is one of the options that is used to interact with a single ros_control node. MoveItControllerManager reads what controller(s) to use from a controllers.yaml file.
MoveIt typically publishes manipulator motion commands to a `JointTrajectoryController <https://github.com/ros-controls/ros2_controllers/tree/master/joint_trajectory_controller>`_. This tutorial assumes MoveGroup is being used to control the robot rather than MoveItCpp or MoveIt Servo. A minimal setup is as follows:

Here we will walk through configuring MoveIt with the controllers on your robot. We will assume that your robot offers a ``FollowJointTrajectory`` action service for the arms on your robot and (optionally) a ``GripperCommand`` service for your gripper. If your robot does not offer this we recommend the `ROS control <http://wiki.ros.org/ros_control>`_ framework for easily adding this functionality around your hardware communication layer.
#. A YAML config file. As best practice, we suggest naming this :code:`moveit_controllers.yaml`. It tells MoveIt which controllers are available, which joints are associated with each, and the MoveIt controller interface type (:code:`FollowJointTrajectory` or :code:`GripperCommand`). `Example controller config file <https://github.com/ros-planning/moveit_resources/blob/ros2/panda_moveit_config/config/panda_controllers.yaml>`_.

YAML Configuration
------------------
The ``controllers.yaml`` configuration file is located in the ``robot_moveit_config/config`` directory of your MoveIt robot config package. This specifies the controller configuration for your robot. Here's an example file for configuring a ``FollowJointTrajectory`` action controller for the ``panda_arm`` and a ``GripperCommand`` gripper controller for its ``hand``: ::
#. A launch file. This launch file must load the :code:`moveit_controllers` yaml file and specify the :code:`moveit_simple_controller_manager/MoveItSimpleControllerManager`. After these yaml files are loaded, they are passed as parameters to the Move Group node. `Example Move Group launch file <https://github.com/ros-planning/moveit_resources/blob/ros2/panda_moveit_config/launch/demo.launch.py>`_.

#. Launch the corresponding :code:`ros2_control` JointTrajectoryControllers. This is separate from the MoveIt2 ecosystem. `Example ros2_control launching <https://github.com/ros-controls/ros2_control_demos>`_. Each JointTrajectoryController provides an action interface. Given the yaml file above, MoveIt automatically connects to this action interface.

#. Note: it is not required to use :code:`ros2_control` for your robot. You could write a proprietary action interface. In practice, 99% of users choose :code:`ros2_control`.

MoveIt Controller Manager
-------------------------
If using the Move Group or MoveItCpp, a MoveItControllerManager (MICM) can be used to manage controller switching. The MICM can parse the joint names in any command coming from MoveIt and activate the appropriate controllers. For example, it can automatically switch between controlling two manipulators in a single joint group at once to a single manipulator. To use a MICM, just set :code:`moveit_manage_controllers = true` in the launch file. `Example MICM launch file <https://github.com/ros-planning/moveit_resources/blob/ros2/panda_moveit_config/launch/demo.launch.py>`_. Frankly, the MICM is a candidate to be deprecated soon and we do not recommend its use.

MoveIt Controller Interfaces
----------------------------

The text above describes launching of a joint trajectory controller action interface. In addition, MoveIt supports parallel-jaw gripper control via action interface. This section describes the parameters of these two options.

#. FollowJointTrajectory Controller Interface

controller_list:
- name: panda_arm_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
- name: hand_controller
action_ns: gripper_action
type: GripperCommand
default: true
parallel: true
joints:
- panda_finger_joint1
- panda_finger_joint2

There are many different parameters that can be used for different types of controllers.

FollowJointTrajectory Controller Interface
------------------------------------------
The parameters are:
* *name*: The name of the controller. (See debugging information below for important notes).
* *action_ns*: The action namespace for the controller. (See debugging information below for important notes).
* *type*: The type of action being used (here FollowJointTrajectory).
* *default*: The default controller is the primary controller chosen by MoveIt for communicating with a particular set of joints.
* *joints*: Names of all the joints that are being addressed by this interface.

GripperCommand Controller Interface
-----------------------------------
#. GripperCommand Controller Interface

The parameters are:
* *name*: The name of the controller. (See debugging information below for important notes).
* *action_ns*: The action namespace for the controller. (See debugging information below for important notes).
Expand All @@ -60,7 +42,9 @@ The parameters are:
Optional Allowed Trajectory Execution Duration Parameters
---------------------------------------------------------

For each controller it is optionally possible to set the *allowed_execution_duration_scaling* and *allowed_goal_duration_margin* parameters. These are controller-specific overrides of the global values *trajectory_execution/allowed_execution_duration_scaling* and *trajectory_execution/allowed_goal_duration_margin*. As opposed to the global values, the contoller-specific ones cannot be dynamically reconfigured at runtime. The parameters are used to compute the allowed trajectory execution duration by scaling the expected execution duration and adding the margin afterwards. If this duration is exceeded the trajectory will be cancelled. The controller-specific parameters can be set as follows ::
(TODO: update for ROS2)

For each controller it is optional to set the *allowed_execution_duration_scaling* and *allowed_goal_duration_margin* parameters. These are controller-specific overrides of the global values *trajectory_execution/allowed_execution_duration_scaling* and *trajectory_execution/allowed_goal_duration_margin*. As opposed to the global values, the contoller-specific ones cannot be dynamically reconfigured at runtime. The parameters are used to compute the allowed trajectory execution duration by scaling the expected execution duration and adding the margin afterwards. If this duration is exceeded the trajectory will be cancelled. The controller-specific parameters can be set as follows ::

controller_list:
- name: arm_controller
Expand All @@ -69,27 +53,12 @@ For each controller it is optionally possible to set the *allowed_execution_dura
allowed_execution_duration_scaling: 1.2
allowed_goal_duration_margin: 0.5

Create the Controller launch file
---------------------------------
Now, create the controller launch file (call it ``robot_moveit_controller_manager.launch.xml`` where ``robot`` is the name of your robot as specified when you created your MoveIt robot config package).

Add the following lines to this file: ::

<launch>
<!-- Set the param that trajectory_execution_manager needs to find the controller plugin -->
<arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager" />
<param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/>
<!-- load controller_list -->
<rosparam file="$(find robot_moveit_config)/config/controllers.yaml"/>
</launch>

MAKE SURE to replace ``robot_moveit_config`` with the correct name of your MoveIt robot config package.

Now, you should be ready to have MoveIt talk to your robot.

Debugging Information
---------------------
The ``FollowJointTrajectory`` or ``GripperCommand`` interfaces on your robot must be communicating in the namespace: ``/name/action_ns``. In the above example, you should be able to see the following topics (using *rostopic list*) on your robot:

(TODO: update for ROS2)

The ``FollowJointTrajectory`` or ``GripperCommand`` interfaces on your robot must be communicating in the namespace: ``/name/action_ns``. In the above example, you should be able to see the following topics (using *ros2 topic list*) on your robot:

* /panda_arm_controller/follow_joint_trajectory/goal
* /panda_arm_controller/follow_joint_trajectory/feedback
Expand All @@ -98,11 +67,13 @@ The ``FollowJointTrajectory`` or ``GripperCommand`` interfaces on your robot mus
* /hand_controller/gripper_action/feedback
* /hand_controller/gripper_action/result

You should also be able to see (using ``rostopic info topic_name``) that the topics are published/subscribed to by the controllers on your robot and also by the **move_group** node.
You should also be able to see (using ``ros2 topic info topic_name``) that the topics are published/subscribed to by the controllers on your robot and also by the **move_group** node.

Remapping /joint_states topic
-----------------------------

(TODO: update for ROS2)

When you run a :doc:`move group node </doc/examples/move_group_interface/move_group_interface_tutorial>`, you may need to remap the topic /joint_states to /robot/joint_states, otherwise MoveIt won't have feedback from the joints. To do this remapping you could make a simple launch file for your node as follows: ::

<node pkg="moveit_ros_move_group" type="move_group" name="any_name" output="screen">
Expand All @@ -127,54 +98,23 @@ MoveIt controller managers, somewhat a misnomer, are the interfaces to your cust

However, for some applications you might desire a more custom controller manager. An example template for starting your custom controller manager is provided :codedir:`here <examples/controller_configuration/src/moveit_controller_manager_example.cpp>`.

Fake Controller Manager
-----------------------

MoveIt comes with a series of fake trajectory controllers that can be used for simulations.
For example, the ``demo.launch`` generated by MoveIt's setup assistant, employs fake controllers for nice visualization in RViz.
For configuration, edit the file ``config/fake_controllers.yaml``, and adjust the desired controller type.
The following controllers are available:

* **interpolate**: perform smooth interpolation between via points - the default for visualization
* **via points**: traverse via points, w/o interpolation in between - useful for visual debugging
* **last point**: warp directly to the last point of the trajectory - fastest method for off-line benchmarking
Simulation
----------

Fake Controller Yaml File
-------------------------

.. code:: yaml
rate: 10 (Hz, used for interpolation controller)
controller_list:
- name: fake_arm_controller
type: interpolate | via points | last point
joints:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
- joint_6
- name: fake_gripper_controller
joints:
[]
In order to load an initial pose, one can have a list of (group, pose) pairs as follows:

.. code:: yaml
initial:
- group: arm
pose: ready
If you do not have a physical robot, :code:`ros2_control` makes it very easy to simulate one. Ignition or Gazebo is not required; RViz is sufficient. All examples in the `ros2_control_demos repo <https://github.com/ros-controls/ros2_control_demos>`_ are simulated.

Controller Switching and Namespaces
-----------------------------------

(TODO: update for ROS2)

All controller names get prefixed by the namespace of their ros_control node. For this reason controller names should not contain slashes, and can't be named ``/``. For a particular node MoveIt can decide which controllers to have started or stopped. Since only controller names with registered allocator plugins are handled over MoveIt, MoveIt takes care of stopping controllers based on their claimed resources if a to-be-started controller needs any of those resources.

Controllers for Multiple Nodes
------------------------------

(TODO: update for ROS2)

MoveItMultiControllerManager can be used for more than one ros_control nodes. It works by creating several MoveItControllerManagers, one for each node. It instantiates them with their respective namespace and takes care of proper delegation. To use it must be added to the launch file. ::

<param name="moveit_controller_manager" value="moveit_ros_control_interface::MoveItMultiControllerManager" />

0 comments on commit c9b8068

Please sign in to comment.