Skip to content

Commit 4377c59

Browse files
sjahrsea-bass
andauthored
Port simplified benchmarking tutorial (#772)
* Add benchmarking tutorial * Update tutorial text * Apply suggestions from code review Co-authored-by: Sebastian Castro <[email protected]> * Address review * Fix link --------- Co-authored-by: Sebastian Castro <[email protected]>
1 parent 3a3358b commit 4377c59

File tree

10 files changed

+201
-178
lines changed

10 files changed

+201
-178
lines changed

CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,7 @@ add_subdirectory(doc/examples/planning_scene)
6262
add_subdirectory(doc/examples/planning_scene_ros_api)
6363
add_subdirectory(doc/examples/realtime_servo)
6464
add_subdirectory(doc/examples/robot_model_and_robot_state)
65+
add_subdirectory(doc/how_to_guides/benchmarking)
6566
add_subdirectory(doc/how_to_guides/isaac_panda)
6667
add_subdirectory(doc/how_to_guides/kinematics_cost_function)
6768
add_subdirectory(doc/how_to_guides/parallel_planning)

doc/examples/benchmarking/benchmarking_tutorial.rst

Lines changed: 0 additions & 177 deletions
This file was deleted.

doc/examples/examples.rst

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,6 @@ Miscellaneous
8181
.. toctree::
8282
:maxdepth: 1
8383

84-
benchmarking/benchmarking_tutorial
8584
dual_arms/dual_arms_tutorial
8685
hybrid_planning/hybrid_planning_tutorial
8786
realtime_servo/realtime_servo_tutorial
Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
install(DIRECTORY launch
2+
DESTINATION share/${PROJECT_NAME}
3+
)
4+
install(DIRECTORY config
5+
DESTINATION share/${PROJECT_NAME}
6+
)
Lines changed: 61 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
How to benchmark your planning pipeline
2+
=======================================
3+
4+
Getting Started
5+
---------------
6+
If you haven't already done so, make sure you've completed the steps in :doc:`Getting Started </doc/tutorials/getting_started/getting_started>`.
7+
8+
The :moveit_codedir:`benchmarking package <moveit_ros/benchmarks>` provides methods to benchmark a MoveIt planning pipeline and aggregate/plot statistics using the OMPL Planner Arena.
9+
The example below demonstrates how the benchmarking can be run.
10+
11+
Example
12+
-------
13+
14+
To run the example you need to install git lfs by running ``git lfs install`` and clone [moveit_benchmark_resources](https://github.com/ros-planning/moveit_benchmark_resources.git) into your workspace.
15+
16+
Start the benchmarks by running: ::
17+
18+
ros2 launch moveit2_tutorials run_benchmarks.launch.py
19+
20+
21+
This will take a while depending on the settings in ``benchmarks.yaml``. The benchmark results will be saved in ``/tmp/moveit_benchmarks/``.
22+
To introspect the benchmark data, the log files need to be converted into a database. This can be done using a script provided in the moveit_ros_benchmarks package: ::
23+
24+
ros2 run moveit_ros_benchmarks moveit_benchmark_statistics.py LOG_FILE_1 ... LOG_FILE_N
25+
26+
This command will create a database containing the data form all benchmark log files included. An easier way to create the database is to create it with all log files from a given repository.
27+
For example, the argument ``/tmp/moveit_benchmarks/*`` can be used to collect all log files in the given directory into a single database. This database is created in the location where the command
28+
above is run in a file names ``benchmark.db``.
29+
30+
The database can be visualized by uploading the the file to `plannerarena.org <http://plannerarena.org>`_ and interactively visualizing the results.
31+
32+
33+
.. image:: planners_benchmark.png
34+
:width: 700px
35+
36+
ROS 2 parameters to configure a benchmark
37+
-----------------------------------------
38+
39+
The benchmarks are configured by a set of ROS 2 parameters. You can learn more about these parameters in the :moveit_codedir:`BenchmarkOptions.h <moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h>` file.
40+
41+
42+
The BenchmarkExecutor Class
43+
---------------------------
44+
45+
This class creates a set of ``MotionPlanRequests`` that respect the parameters given in the supplied instance of ``BenchmarkOptions`` and then executes the requests on each of the planners specified. From the ``BenchmarkOptions``, queries, ``goal_constraints``, and ``trajectory_constraints`` are treated as separate queries. If a set of ``start_states`` is specified, each query, ``goal_constraint``, and ``trajectory_constraint`` is attempted with each start state (existing start states from a query are ignored). Similarly, the (optional) set of path constraints is combined combinatorially with the start query and start ``goal_constraint`` pairs (existing ``path_constraint`` from a query are ignored). The workspace, if specified, overrides any existing workspace parameters.
46+
47+
The benchmarking pipeline does not utilize ``MoveGroup``.
48+
Instead, the planning pipelines are initialized and run directly including all specified ``PlanningRequestAdapters``.
49+
This is especially useful for benchmarking the effects of smoothing adapters.
50+
51+
It is possible to customize a benchmark run by deriving a class from ``BenchmarkExecutor`` and overriding one or more of the virtual functions.
52+
For instance, overriding the functions ``initializeBenchmarks()`` or ``loadBenchmarkQueryData()`` allows to specify the benchmark queries directly and to provide a custom planning scene without using ROS warehouse.
53+
54+
Additionally, a set of functions exists for ease of customization in derived classes:
55+
56+
- ``preRunEvent``: invoked immediately before each call to solve
57+
- ``postRunEvent``: invoked immediately after each call to solve
58+
- ``plannerSwitchEvent``: invoked when the planner changes during benchmarking
59+
- ``querySwitchEvent``: invoked before a new benchmark problem begin execution
60+
61+
Note, in the above, a benchmark is a concrete instance of a ``PlanningScene``, start state, goal constraints / ``trajectory_constraints``, and (optionally) ``path_constraints``. A run is one attempt by a specific planner to solve the benchmark.
Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
planning_pipelines:
2+
# MoveIt cpp
3+
pipeline_names: ["ompl", "ompl_rrtc", "stomp", "pilz_industrial_motion_planner"]
Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
# A detailed description for all parameters can be found in BenchmarkOptions.h
2+
3+
parameters:
4+
name: FullBenchmark
5+
runs: 1
6+
group: panda_arm # Required
7+
timeout: 1.5
8+
output_directory: /tmp/moveit_benchmarks/
9+
start_states_regex: ready
10+
planning_pipelines:
11+
# Benchmark tool
12+
pipelines: [OMPL_ANY, OMPL_RRTC, CHOMP, PILZ_LIN]
13+
OMPL_ANY:
14+
name: ompl
15+
planners:
16+
- APSConfigDefault
17+
OMPL_RRTC:
18+
name: ompl_rrtc
19+
planners:
20+
- RRTConnectkConfigDefault
21+
CHOMP:
22+
name: stomp
23+
planners:
24+
- stomp
25+
PILZ_LIN:
26+
name: pilz_industrial_motion_planner
27+
planners:
28+
- LIN
29+
parallel_pipelines: [ompl_pilz_chomp]
30+
ompl_pilz_chomp:
31+
pipelines: [ompl_rrtc, stomp, pilz_industrial_motion_planner]
32+
planner_ids: [RRTConnectkConfigDefault, stomp, LIN]
Lines changed: 97 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,97 @@
1+
import os
2+
import yaml
3+
from launch import LaunchDescription
4+
from launch_ros.actions import Node
5+
from ament_index_python.packages import get_package_share_directory
6+
from moveit_configs_utils import MoveItConfigsBuilder
7+
from launch_param_builder import ParameterBuilder
8+
9+
10+
def load_yaml(package_name, file_path):
11+
package_path = get_package_share_directory(package_name)
12+
absolute_file_path = os.path.join(package_path, file_path)
13+
14+
try:
15+
with open(absolute_file_path, "r") as file:
16+
return yaml.safe_load(file)
17+
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
18+
return None
19+
20+
21+
def generate_launch_description():
22+
23+
moveit_ros_benchmarks_config = (
24+
ParameterBuilder("moveit2_tutorials")
25+
.yaml(
26+
parameter_namespace="benchmark_config",
27+
file_path="config/benchmarks.yaml",
28+
)
29+
.to_dict()
30+
)
31+
32+
moveit_configs = (
33+
MoveItConfigsBuilder("moveit_resources_panda")
34+
.robot_description(file_path="config/panda.urdf.xacro")
35+
.planning_pipelines("ompl", ["ompl", "stomp", "pilz_industrial_motion_planner"])
36+
.moveit_cpp(
37+
os.path.join(
38+
get_package_share_directory("moveit2_tutorials"),
39+
"config",
40+
"benchmarking_moveit_cpp.yaml",
41+
)
42+
)
43+
.to_moveit_configs()
44+
)
45+
46+
# Load additional OMPL pipeline
47+
ompl_planning_pipeline_config = {
48+
"ompl_rrtc": {
49+
"planning_plugin": "ompl_interface/OMPLPlanner",
50+
"request_adapters": """\
51+
default_planner_request_adapters/AddTimeOptimalParameterization \
52+
default_planner_request_adapters/FixWorkspaceBounds \
53+
default_planner_request_adapters/FixStartStateBounds \
54+
default_planner_request_adapters/FixStartStateCollision \
55+
default_planner_request_adapters/FixStartStatePathConstraints \
56+
""",
57+
"start_state_max_bounds_error": 0.1,
58+
}
59+
}
60+
ompl_planning_yaml = load_yaml(
61+
"moveit_resources_panda_moveit_config", "config/ompl_planning.yaml"
62+
)
63+
ompl_planning_pipeline_config["ompl_rrtc"].update(ompl_planning_yaml)
64+
65+
sqlite_database = (
66+
get_package_share_directory("moveit_benchmark_resources")
67+
+ "/databases/panda_kitchen_test_db.sqlite"
68+
)
69+
70+
warehouse_ros_config = {
71+
"warehouse_plugin": "warehouse_ros_sqlite::DatabaseConnection",
72+
"benchmark_config": {
73+
"warehouse": {
74+
"warehouse_plugin": "warehouse_ros_sqlite::DatabaseConnection",
75+
"host": sqlite_database,
76+
"port": 33828,
77+
"scene_name": "", # If scene name is empty, all scenes will be used
78+
"queries_regex": ".*",
79+
},
80+
},
81+
}
82+
83+
# moveit_ros_benchmark demo executable
84+
moveit_ros_benchmarks_node = Node(
85+
name="moveit_run_benchmark",
86+
package="moveit_ros_benchmarks",
87+
executable="moveit_run_benchmark",
88+
output="screen",
89+
parameters=[
90+
moveit_ros_benchmarks_config,
91+
moveit_configs.to_dict(),
92+
warehouse_ros_config,
93+
ompl_planning_pipeline_config,
94+
],
95+
)
96+
97+
return LaunchDescription([moveit_ros_benchmarks_node])
File renamed without changes.

0 commit comments

Comments
 (0)