Skip to content

Commit

Permalink
Adds a benchmark for IrisInConfigurationSpace (RobotLocomotion#19771)
Browse files Browse the repository at this point in the history
This benchmark plants a flag before we start optimizing the
IrisInConfigurationSpace runtimes.
  • Loading branch information
RussTedrake authored Jul 23, 2023
1 parent 5b48a3d commit 23e3325
Show file tree
Hide file tree
Showing 8 changed files with 474 additions and 4 deletions.
11 changes: 11 additions & 0 deletions examples/manipulation_station/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,17 @@ load("//tools/skylark:test_tags.bzl", "vtk_test_tags")

models_filegroup(
name = "models",
extra_srcs = [
"@drake_models//:manipulation_station/bin.mtl",
"@drake_models//:manipulation_station/bin.obj",
"@drake_models//:manipulation_station/bin.png",
"@drake_models//:manipulation_station/table_wide.mtl",
"@drake_models//:manipulation_station/table_wide.obj",
"@drake_models//:manipulation_station/table_wide.png",
"@drake_models//:manipulation_station/shelves.mtl",
"@drake_models//:manipulation_station/shelves.obj",
"@drake_models//:manipulation_station/shelves.png",
],
visibility = ["//visibility:public"],
)

Expand Down
77 changes: 77 additions & 0 deletions examples/manipulation_station/models/bin2.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
<?xml version="1.0"?>
<sdf version="1.7">
<model name="bin_model">
<!--
Axes:
+X - Pointing towards front
+Y - Pointing to left side
+Z - Up
Origin:
(0, 0, 0) at the center bottom of the bin
-->
<link name="bin_base">
<inertial>
<mass>18.70</mass>
<inertia>
<ixx>0.79</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.53</iyy>
<iyz>0</iyz>
<izz>1.2</izz>
</inertia>
</inertial>
<visual name="visual">
<pose>0 0 0 0 0 1.570796</pose>
<geometry>
<mesh>
<uri>package://drake_models/manipulation_station/bin.obj</uri>
</mesh>
</geometry>
</visual>
<collision name="front">
<pose>0.2025 0 0.105 0 0 0</pose>
<geometry>
<box>
<size>0.015 0.56 0.21</size>
</box>
</geometry>
</collision>
<collision name="back">
<pose>-0.2025 0 0.105 0 0 0</pose>
<geometry>
<box>
<size>0.015 0.56 0.21</size>
</box>
</geometry>
</collision>
<collision name="left">
<pose>0 0.2725 0.105 0 0 0</pose>
<geometry>
<box>
<size>0.42 0.015 0.21</size>
</box>
</geometry>
</collision>
<collision name="right">
<pose>0 -0.2725 0.105 0 0 0</pose>
<geometry>
<box>
<size>0.42 0.015 0.21</size>
</box>
</geometry>
</collision>
<collision name="bottom">
<pose>0.0 0.0 0.0075 0 0 0</pose>
<geometry>
<box>
<size>0.42 0.56 0.015</size>
</box>
</geometry>
</collision>
</link>
<frame name="bin_front_top_center">
<pose relative_to="bin_base">0.22 0 0.21 0 0 0</pose>
</frame>
</model>
</sdf>
71 changes: 71 additions & 0 deletions examples/manipulation_station/models/shelves.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
<?xml version="1.0"?>
<sdf version="1.7">
<model name="shelves">
<link name="shelves_body">
<visual name="shelves_visual">
<pose> 0 0 0 0 0 3.14159</pose>
<geometry>
<mesh>
<uri>package://drake_models/manipulation_station/shelves.obj</uri>
</mesh>
</geometry>
</visual>
<collision name="right_wall">
<pose> 0 0.292 0 0 0 0</pose>
<geometry>
<box>
<size>0.3 0.016 0.783</size>
</box>
</geometry>
</collision>
<collision name="left_wall">
<pose> 0 -0.292 0 0 0 0</pose>
<geometry>
<box>
<size>0.3 0.016 0.783</size>
</box>
</geometry>
</collision>
<collision name="top">
<pose> 0 0 0.3995 0 0 0</pose>
<geometry>
<box>
<size>0.3 0.6 0.016</size>
</box>
</geometry>
</collision>
<collision name="shelf_lower">
<pose> 0 0 -0.13115 0 0 0</pose>
<geometry>
<box>
<size>0.3 0.6 0.016</size>
</box>
</geometry>
</collision>
<collision name="shelf_upper">
<pose> 0 0 0.13115 0 0 0</pose>
<geometry>
<box>
<size>0.3 0.6 0.016</size>
</box>
</geometry>
</collision>
<collision name="bottom">
<pose> 0 0 -0.3995 0 0 0</pose>
<geometry>
<box>
<size>0.3 0.6 0.016</size>
</box>
</geometry>
</collision>
<collision name="back">
<pose> -0.142 0 0 0 0 0</pose>
<geometry>
<box>
<size>0.016 0.6 0.783</size>
</box>
</geometry>
</collision>
</link>
</model>
</sdf>
22 changes: 22 additions & 0 deletions examples/manipulation_station/models/table_wide.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<?xml version="1.0"?>
<sdf version="1.7">
<model name="table">
<link name="table_body">
<visual name="table_visual">
<geometry>
<mesh>
<uri>package://drake_models/manipulation_station/table_wide.obj</uri>
</mesh>
</geometry>
</visual>
<collision name="table_top">
<pose> 0 0 -0.05 0 0 0</pose>
<geometry>
<box>
<size>1.5 2.1875 0.1</size>
</box>
</geometry>
</collision>
</link>
</model>
</sdf>
27 changes: 27 additions & 0 deletions geometry/benchmarking/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,33 @@ load("//tools/skylark:test_tags.bzl", "vtk_test_tags")

package(default_visibility = ["//visibility:private"])

drake_cc_googlebench_binary(
name = "iris_in_configuration_space_benchmarks",
srcs = ["iris_in_configuration_space_benchmarks.cc"],
add_test_rule = True,
data = [
"//examples/manipulation_station:models",
"//manipulation/models/iiwa_description:models",
"//manipulation/models/wsg_50_description:models",
],
test_args = [
"--test",
],
test_timeout = "moderate",
deps = [
"//geometry/optimization:iris",
"//multibody/inverse_kinematics",
"//multibody/plant",
"//tools/performance:fixture_common",
"//tools/performance:gflags_main",
],
)

drake_py_experiment_binary(
name = "iris_in_configuration_space_experiment",
googlebench_binary = ":iris_in_configuration_space_benchmarks",
)

drake_cc_googlebench_binary(
name = "mesh_intersection_benchmark",
srcs = ["mesh_intersection_benchmark.cc"],
Expand Down
20 changes: 18 additions & 2 deletions geometry/benchmarking/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,9 @@ Runtime Performance Benchmarks for Geometry Operations

## render

$ bazel run //geometry/benchmarking:render_experiment -- --output_dir=foo
```
$ bazel run //geometry/benchmarking:render_experiment -- --output_dir=foo
```

Benchmark program to help characterize the relative costs of different
RenderEngine implementations with varying scene complexity and rendering. It is
Expand All @@ -15,13 +17,27 @@ renderer choice.

## mesh_intersection

$ bazel run //geometry/benchmarking:mesh_intersection_experiment -- --output_dir=foo
```
$ bazel run //geometry/benchmarking:mesh_intersection_experiment -- --output_dir=foo
```

Benchmark program to evaluate bounding volume hierarchy impact on mesh-mesh
intersections across varying mesh attributes and overlaps. It is targeted toward
developers during the process of optimizing the performance of hydroelastic
contact and may be removed once sufficient work has been done in that effort.

## iris_in_configuration_space

Note: This benchmark requires [SNOPT](https://drake.mit.edu/bazel.html#snopt).

```
$ bazel run //geometry/benchmarking:iris_in_configuration_space_experiment -- --output_dir=foo
```

This benchmark is provided to help understand the implications of changes the
will impact the performance of the IrisInConfigurationSpace algorithm. It
should grow to include a number of our most important/relevant examples.

# Additional information

Documentation for command line arguments is here:
Expand Down
Loading

0 comments on commit 23e3325

Please sign in to comment.