Skip to content

Commit e9c7525

Browse files
Backport of Pilz examples and update to ROS2 (#548) to humble (#797)
* Pilz examples and update to ROS2 (#548) * Add bare-bones Pilz code examples * Fill in Pilz MTC example * Clean up MTC example * Fill in MoveGroup Interface example + more cleanup * Update docs * clang-format * Fix HTML targets * Update code links to use codedir * PR comments * Fix URL (cherry picked from commit 7498cc2) # Conflicts: # CMakeLists.txt * Fix conflicts from mergify bot --------- Co-authored-by: Sebastian Castro <[email protected]> Co-authored-by: Sebastian Castro <[email protected]>
1 parent e6041e7 commit e9c7525

File tree

7 files changed

+635
-72
lines changed

7 files changed

+635
-72
lines changed

CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,7 @@ add_subdirectory(doc/examples/move_group_interface)
6767
# add_subdirectory(doc/examples/move_group_python_interface)
6868
# add_subdirectory(doc/examples/perception_pipeline)
6969
# add_subdirectory(doc/examples/pick_place)
70+
add_subdirectory(doc/examples/pilz_industrial_motion_planner)
7071
# add_subdirectory(doc/examples/planning)
7172
add_subdirectory(doc/examples/planning_scene)
7273
add_subdirectory(doc/examples/planning_scene_ros_api)
Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
add_executable(pilz_move_group src/pilz_move_group.cpp)
2+
target_include_directories(pilz_move_group PUBLIC include)
3+
ament_target_dependencies(pilz_move_group ${THIS_PACKAGE_INCLUDE_DEPENDS})
4+
5+
add_executable(pilz_mtc src/pilz_mtc.cpp)
6+
target_include_directories(pilz_mtc PUBLIC include)
7+
ament_target_dependencies(pilz_mtc ${THIS_PACKAGE_INCLUDE_DEPENDS})
8+
9+
install(
10+
TARGETS
11+
pilz_move_group
12+
pilz_mtc
13+
DESTINATION
14+
lib/${PROJECT_NAME}
15+
)
16+
17+
install(DIRECTORY launch
18+
DESTINATION share/${PROJECT_NAME}
19+
)
Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
from launch import LaunchDescription
2+
from launch_ros.actions import Node
3+
from moveit_configs_utils import MoveItConfigsBuilder
4+
5+
6+
def generate_launch_description():
7+
moveit_config = MoveItConfigsBuilder("moveit_resources_panda").to_dict()
8+
9+
# Pilz + MTC Demo node
10+
pilz_mtc_demo = Node(
11+
package="moveit2_tutorials",
12+
executable="pilz_mtc",
13+
output="screen",
14+
parameters=[
15+
moveit_config,
16+
],
17+
)
18+
19+
return LaunchDescription([pilz_mtc_demo])

doc/examples/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst

Lines changed: 113 additions & 72 deletions
Original file line numberDiff line numberDiff line change
@@ -1,56 +1,48 @@
1-
:moveit1:
2-
3-
..
4-
Once updated for MoveIt 2, remove all lines above title (including this comment and :moveit1: tag)
5-
61
Pilz Industrial Motion Planner
72
==============================
83

94
``pilz_industrial_motion_planner`` provides a trajectory generator to plan standard robot
10-
motions like PTP, LIN, CIRC with the interface of a MoveIt PlannerManager
11-
plugin.
5+
motions like point-to-point, linear, and circular with MoveIt.
126

13-
User Interface MoveGroup
14-
------------------------
15-
16-
This package implements the ``planning_interface::PlannerManager``
17-
interface of MoveIt. By loading the corresponding planning pipeline
18-
(``pilz_industrial_motion_planner_planning_pipeline.launch.xml`` in your
7+
By loading the corresponding planning pipeline
8+
(``pilz_industrial_motion_planner_planning_planner.yaml`` in your
199
``*_moveit_config`` package), the trajectory generation
20-
functionalities can be accessed through the user interface (c++, python
21-
or rviz) provided by the ``move_group`` node, e.g.
22-
``/plan_kinematics_path`` service and ``/move_group`` action. For
23-
detailed usage tutorials please refer to :doc:`/doc/examples/move_group_interface/move_group_interface_tutorial`.
10+
functionalities can be accessed through the user interface (C++, Python
11+
or RViz) provided by the ``move_group`` node, e.g.
12+
``/plan_kinematic_path`` service and ``/move_action`` action.
13+
For detailed usage tutorials, please refer to
14+
:doc:`/doc/examples/moveit_cpp/moveitcpp_tutorial` and
15+
:doc:`/doc/examples/move_group_interface/move_group_interface_tutorial`.
2416

2517
Joint Limits
2618
------------
2719

28-
For all commands the planner uses maximum velocities and accelerations from
29-
the parameter server. Using the MoveIt setup assistant the file ``joint_limits.yaml``
20+
The planner uses maximum velocities and accelerations from the
21+
parameters of the ROS node that is operating the Pilz planning pipeline.
22+
Using the MoveIt Setup Assistant the file ``joint_limits.yaml``
3023
is auto-generated with proper defaults and loaded during startup.
3124

32-
The limits on the parameter server override the limits from the URDF robot description.
25+
The specified limits override the limits from the URDF robot description.
3326
Note that while setting position limits and velocity limits is possible
34-
in both the URDF and the parameter server setting acceleration limits is
35-
only possible via the parameter server. In extension to the common
36-
``has_acceleration`` and ``max_acceleration`` parameter we added the
37-
ability to also set ``has_deceleration`` and
38-
``max_deceleration``\ (<0.0).
27+
in both the URDF and a parameter file, setting acceleration limits is
28+
only possible using a parameter file. In addition to the common
29+
``has_acceleration`` and ``max_acceleration`` parameters, we added the
30+
ability to also set ``has_deceleration`` and ``max_deceleration``\ (<0.0).
3931

4032
The limits are merged under the premise that the limits from the
41-
parameter server must be stricter or at least equal to the parameters
33+
node parameters must be stricter or at least equal to the parameters
4234
set in the URDF.
4335

44-
Currently the calculated trajectory will respect the limits by using the
36+
Currently, the calculated trajectory will respect the limits by using the
4537
strictest combination of all limits as a common limit for all joints.
4638

4739
Cartesian Limits
4840
----------------
4941

50-
For cartesian trajectory generation (LIN/CIRC) the planner needs an
51-
information about the maximum speed in 3D cartesian space. Namely
42+
For Cartesian trajectory generation (LIN/CIRC), the planner needs
43+
information about the maximum speed in 3D Cartesian space. Namely,
5244
translational/rotational velocity/acceleration/deceleration need to be
53-
set on the parameter server like this:
45+
set in the node parameters like this:
5446

5547
.. code:: yaml
5648
@@ -60,22 +52,25 @@ set on the parameter server like this:
6052
max_trans_dec: -5
6153
max_rot_vel: 1.57
6254
55+
You can specify Cartesian velocity and acceleration limits in a file named
56+
``pilz_cartesian_limits.yaml`` in your ``*_moveit_config`` package.
57+
6358
The planners assume the same acceleration ratio for translational and
64-
rotational trapezoidal shapes. So the rotational acceleration is
65-
calculated as ``max\_trans\_acc / max\_trans\_vel \* max\_rot\_vel`` (and
66-
for deceleration accordingly).
59+
rotational trapezoidal shapes. The rotational acceleration is
60+
calculated as ``max_trans_acc / max_trans_vel * max_rot_vel``
61+
(and for deceleration accordingly).
6762

6863
Planning Interface
6964
------------------
7065

71-
This package uses ``moveit_msgs::MotionPlanRequest`` and ``moveit_msgs::MotionPlanResponse``
66+
This package uses ``moveit_msgs::msgs::MotionPlanRequest`` and ``moveit_msgs::msg::MotionPlanResponse``
7267
as input and output for motion planning. The parameters needed for each planning algorithm
7368
are explained below.
7469

75-
For a general introduction on how to fill a ``MotionPlanRequest`` see
70+
For a general introduction on how to fill a ``MotionPlanRequest``, see
7671
:ref:`move_group_interface-planning-to-pose-goal`.
7772

78-
You can specify "PTP", "LIN" or "CIRC" as the ``planner\_id``of the ``MotionPlanRequest``.
73+
You can specify ``"PTP"``, ``"LIN"`` or ``"CIRC"`` as the ``planner_id`` of the ``MotionPlanRequest``.
7974

8075
The PTP motion command
8176
----------------------
@@ -95,12 +90,12 @@ phases as the lead axis.
9590
PTP Input Parameters in ``moveit_msgs::MotionPlanRequest``
9691
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
9792

98-
- ``planner_id``: PTP
99-
- ``group_name``: name of the planning group
93+
- ``planner_id``: ``"PTP"``
94+
- ``group_name``: the name of the planning group
10095
- ``max_velocity_scaling_factor``: scaling factor of maximal joint velocity
10196
- ``max_acceleration_scaling_factor``: scaling factor of maximal joint acceleration/deceleration
102-
- ``start_state/joint_state/(name, position and velocity``: joint name/position/velocity(optional) of the start state.
103-
- ``goal_constraints`` (goal can be given in joint space or Cartesian space)
97+
- ``start_state/joint_state/(name, position and velocity)``: joint name/position/velocity (optional) of the start state.
98+
- ``goal_constraints``: (goal can be given in joint space or Cartesian space)
10499
- for a goal in joint space
105100
- ``goal_constraints/joint_constraints/joint_name``: goal joint name
106101
- ``goal_constraints/joint_constraints/position``: goal joint position
@@ -123,13 +118,13 @@ PTP Planning Result in ``moveit_msg::MotionPlanResponse``
123118
positions/velocities/accelerations of all joints (same order as the
124119
joint names) and time from start. The last point will have zero
125120
velocity and acceleration.
126-
- ``group_name``: name of the planning group
121+
- ``group_name``: the name of the planning group
127122
- ``error_code/val``: error code of the motion planning
128123

129124
The LIN motion command
130125
----------------------
131126

132-
This planner generates linear Cartesian trajectory between goal and
127+
This planner generates a linear Cartesian trajectory between goal and
133128
start poses. The planner uses the Cartesian limits to generate a
134129
trapezoidal velocity profile in Cartesian space. The translational
135130
motion is a linear interpolation between start and goal position vector.
@@ -143,8 +138,8 @@ violation of joint space limits.
143138
LIN Input Parameters in ``moveit_msgs::MotionPlanRequest``
144139
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
145140

146-
- ``planner_id``: LIN
147-
- ``group_name``: name of the planning group
141+
- ``planner_id``: ``"LIN"``
142+
- ``group_name``: the name of the planning group
148143
- ``max_velocity_scaling_factor``: scaling factor of maximal Cartesian
149144
translational/rotational velocity
150145
- ``max_acceleration_scaling_factor``: scaling factor of maximal
@@ -184,7 +179,7 @@ LIN Planning Result in ``moveit_msg::MotionPlanResponse``
184179
positions/velocities/accelerations of all joints (same order as the
185180
joint names) and time from start. The last point will have zero
186181
velocity and acceleration.
187-
- ``group_name``: name of the planning group
182+
- ``group_name``: the name of the planning group
188183
- ``error_code/val``: error code of the motion planning
189184

190185
The CIRC motion command
@@ -206,16 +201,16 @@ velocity/acceleration/deceleration need to be set and the planner uses
206201
these limits to generate a trapezoidal velocity profile in Cartesian
207202
space. The rotational motion is quaternion slerp between start and goal
208203
orientation. The translational and rotational motion is synchronized in
209-
time. This planner only accepts start state with zero velocity. Planning
204+
time. This planner only accepts start state with zero velocity. The planning
210205
result is a joint trajectory. The user needs to adapt the Cartesian
211206
velocity/acceleration scaling factor if motion plan fails due to
212207
violation of joint limits.
213208

214209
CIRC Input Parameters in ``moveit_msgs::MotionPlanRequest``
215210
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
216211

217-
- ``planner_id``: CIRC
218-
- ``group_name``: name of the planning group
212+
- ``planner_id``: ``"CIRC"``
213+
- ``group_name``: the name of the planning group
219214
- ``max_velocity_scaling_factor``: scaling factor of maximal Cartesian
220215
translational/rotational velocity
221216
- ``max_acceleration_scaling_factor``: scaling factor of maximal
@@ -262,42 +257,87 @@ CIRC Planning Result in ``moveit_msg::MotionPlanResponse``
262257
positions/velocities/accelerations of all joints (same order as the
263258
joint names) and time from start. The last point will have zero
264259
velocity and acceleration.
265-
- ``group_name``: name of the planning group
260+
- ``group_name``: the name of the planning group
266261
- ``error_code/val``: error code of the motion planning
267262

268-
Example
269-
-------
263+
Examples
264+
--------
270265

271266
By running
272267

273268
::
274269

275-
roslaunch prbt_moveit_config demo.launch
270+
ros2 launch moveit2_tutorials demo.launch.py rviz_config:=panda_hello_moveit.rviz
276271

277-
the user can interact with the planner through rviz.
272+
you can interact with the planner through the RViz MotionPlanning panel.
278273

279274
.. figure:: rviz_planner.png
280275
:alt: rviz figure
281276

277+
To use the planner through the MoveGroup Interface, refer to
278+
:codedir:`the MoveGroup Interface C++ example <examples/pilz_industrial_motion_planner/src/pilz_move_group.cpp>`.
279+
To run this, execute the following commands in separate Terminals:
280+
281+
::
282+
283+
ros2 launch moveit2_tutorials demo.launch.py rviz_config:=panda_hello_moveit.rviz
284+
ros2 run moveit2_tutorials pilz_move_group
285+
286+
287+
To use the planner using MoveIt Task Constructor, refer to
288+
:codedir:`the MoveIt Task Constructor C++ example <examples/pilz_industrial_motion_planner/src/pilz_mtc.cpp>`.
289+
To run this, execute the following commands in separate Terminals:
290+
291+
::
292+
293+
ros2 launch moveit2_tutorials mtc_demo.launch.py
294+
ros2 launch moveit2_tutorials pilz_mtc.launch.py
295+
282296
Using the planner
283297
-----------------
284298

285299
The *pilz_industrial_motion_planner::CommandPlanner* is provided as a MoveIt Motion Planning
286300
Pipeline and, therefore, can be used with all other manipulators using
287301
MoveIt. Loading the plugin requires the param
288-
``/move_group/planning_plugin`` to be set to ``pilz_industrial_motion_planner::CommandPlanner``
302+
``/move_group/<pipeline_name>/planning_plugin`` to be set to ``pilz_industrial_motion_planner/CommandPlanner``
289303
before the ``move_group`` node is started.
304+
For example, the `panda_moveit_config package
305+
<https://github.com/ros-planning/moveit_resources/blob/ros2/panda_moveit_config>`_
306+
has a ``pilz_industrial_motion_planner`` pipeline set up as follows:
307+
308+
309+
::
310+
311+
ros2 param get /move_group pilz_industrial_motion_planner.planning_plugin
312+
313+
String value is: pilz_industrial_motion_planner/CommandPlanner
314+
290315

291-
To use the command planner cartesian limits have to be defined. The
316+
To use the command planner, Cartesian limits have to be defined. The
292317
limits are expected to be under the namespace
293-
``<robot_description>_planning``. Where ``<robot_description>`` refers
294-
to the parameter under which the URDF is loaded. E.g. if the URDF was
295-
loaded into ``/robot_description`` the cartesian limits have to be
296-
defined at ``/robot_description_planning``.
318+
``<robot_description>_planning``, where ``<robot_description>`` refers
319+
to the parameter name under which the URDF is loaded.
320+
For example, if the URDF was loaded into ``/robot_description`` the
321+
Cartesian limits have to be defined at ``/robot_description_planning``.
322+
323+
You can set these using a ``pilz_cartesian_limits.yaml`` file in your
324+
``*_moveit_config`` package.
325+
An example showing this file can be found in `panda_moveit_config
326+
<https://github.com/ros-planning/moveit_resources/blob/ros2/panda_moveit_config/config/pilz_cartesian_limits.yaml>`_.
327+
328+
To verify the limits were set correctly, you can check the parameters for your
329+
``move_group`` node. For example,
330+
331+
::
332+
333+
ros2 param list /move_group --filter .*cartesian_limits
334+
335+
/move_group:
336+
robot_description_planning.cartesian_limits.max_rot_vel
337+
robot_description_planning.cartesian_limits.max_trans_acc
338+
robot_description_planning.cartesian_limits.max_trans_dec
339+
robot_description_planning.cartesian_limits.max_trans_vel
297340

298-
An example showing the cartesian limits which have to be defined can be
299-
found in `prbt_moveit_config
300-
<https://github.com/ros-planning/moveit_resources/blob/master/prbt_moveit_config/config/cartesian_limits.yaml>`_.
301341

302342
Sequence of multiple segments
303343
=============================
@@ -316,9 +356,10 @@ multiple groups (e.g. "Manipulator", "Gripper")
316356
User interface sequence capability
317357
----------------------------------
318358

319-
A specialized MoveIt capability takes a
320-
``moveit_msgs::MotionSequenceRequest`` as input. The request contains a
321-
list of subsequent goals as described above and an additional
359+
A specialized MoveIt functionality known as the
360+
:moveit_codedir:`command list manager<moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h>`
361+
takes a ``moveit_msgs::msg::MotionSequenceRequest`` as input.
362+
The request contains a list of subsequent goals as described above and an additional
322363
``blend_radius`` parameter. If the given ``blend_radius`` in meter is
323364
greater than zero, the corresponding trajectory is merged together with
324365
the following goal such that the robot does not stop at the current
@@ -330,8 +371,8 @@ the trajectory it would have taken without blending.
330371
.. figure:: blend_radius.png
331372
:alt: blend figure
332373

333-
Implementation details are available `as pdf
334-
<https://github.com/ros-planning/moveit/blob/master/moveit_planners/pilz_industrial_motion_planner/doc/MotionBlendAlgorithmDescription.pdf>`_.
374+
Implementation details are available
375+
:moveit_codedir:`as PDF<moveit_planners/pilz_industrial_motion_planner/doc/MotionBlendAlgorithmDescription.pdf>`.
335376

336377
Restrictions for ``MotionSequenceRequest``
337378
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
@@ -345,24 +386,24 @@ Restrictions for ``MotionSequenceRequest``
345386
Action interface
346387
~~~~~~~~~~~~~~~~
347388

348-
In analogy to the ``MoveGroup`` action interface the user can plan and
389+
In analogy to the ``MoveGroup`` action interface, the user can plan and
349390
execute a ``moveit_msgs::MotionSequenceRequest`` through the action server
350391
at ``/sequence_move_group``.
351392

352393
In one point the ``MoveGroupSequenceAction`` differs from the standard
353394
MoveGroup capability: If the robot is already at the goal position, the
354395
path is still executed. The underlying PlannerManager can check, if the
355-
constraints of an individual ``moveit_msgs::MotionPlanRequest`` are
396+
constraints of an individual ``moveit_msgs::msg::MotionPlanRequest`` are
356397
already satisfied but the ``MoveGroupSequenceAction`` capability doesn't
357398
implement such a check to allow moving on a circular or comparable path.
358399

359-
See the ``pilz_robot_programming`` package for an `example python script
400+
See the ``pilz_robot_programming`` package for an `ROS1 python script
360401
<https://github.com/PilzDE/pilz_industrial_motion/blob/melodic-devel/pilz_robot_programming/examples/demo_program.py>`_
361402
that shows how to use the capability.
362403

363404
Service interface
364405
~~~~~~~~~~~~~~~~~
365406

366407
The service ``plan_sequence_path`` allows the user to generate a joint
367-
trajectory for a ``moveit_msgs::MotionSequenceRequest``. The trajectory is
368-
returned and not executed.
408+
trajectory for a ``moveit_msgs::msg::MotionSequenceRequest``.
409+
The trajectory is returned and not executed.
33.4 KB
Loading

0 commit comments

Comments
 (0)