Skip to content

Commit

Permalink
Use moveit_benchmark_resources database instead of one in the tutorial
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed Sep 22, 2023
1 parent 1e62aac commit 9cc9696
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 2 deletions.
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@ def generate_launch_description():
)

sqlite_database = (
get_package_share_directory("moveit2_tutorials")
+ "/data/kitchen_panda_db.sqlite"
get_package_share_directory("moveit_benchmark_resources")
+ "/config/panda_test_db.sqlite"
)

print(sqlite_database)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@ If the database file does not exist yet, an empty database will be created.
Connecting to the storage backend
---------------------------------

To run the demo 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.

After choosing the storage plugin and configuring the launch.py file,
run RViz using ::

Expand Down
4 changes: 4 additions & 0 deletions moveit2_tutorials.repos
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,10 @@ repositories:
type: git
url: https://github.com/ros-planning/moveit_resources
version: ros2
moveit_benchmark_resources:
type: git
url: https://github.com/ros-planning/moveit_benchmark_resources.git
version: main
moveit_msgs:
type: git
url: https://github.com/ros-planning/moveit_msgs
Expand Down

0 comments on commit 9cc9696

Please sign in to comment.