Skip to content

Commit 419bdb2

Browse files
authored
Add database for warehouse tutorial and bump CMake version (#509)
* Add example database to persistant_scene_demo * Bump CMake versions * Update launch file name in rst file * Update wrong launch file name
1 parent b398d5c commit 419bdb2

File tree

6 files changed

+21
-7
lines changed

6 files changed

+21
-7
lines changed

CMakeLists.txt

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
cmake_minimum_required(VERSION 3.10.2)
1+
cmake_minimum_required(VERSION 3.22)
22
project(moveit2_tutorials)
33

44
# Common cmake code applied to all moveit packages
@@ -57,6 +57,7 @@ add_subdirectory(doc/examples/motion_planning_api)
5757
add_subdirectory(doc/examples/motion_planning_pipeline)
5858
add_subdirectory(doc/examples/move_group_interface)
5959
add_subdirectory(doc/examples/moveit_cpp)
60+
add_subdirectory(doc/examples/persistent_scenes_and_states)
6061
add_subdirectory(doc/examples/planning_scene_ros_api)
6162
add_subdirectory(doc/examples/planning_scene)
6263
add_subdirectory(doc/examples/realtime_servo)

doc/examples/dual_arms/dual_arm_panda_moveit_config/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
cmake_minimum_required(VERSION 3.10.2)
1+
cmake_minimum_required(VERSION 3.22)
22
project(dual_arm_panda_moveit_config)
33
find_package(ament_cmake REQUIRED)
44

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 data
5+
DESTINATION share/${PROJECT_NAME}
6+
)
1.27 MB
Binary file not shown.

doc/examples/persistent_scenes_and_states/move_group.launch.py renamed to doc/examples/persistent_scenes_and_states/launch/persistent_scenes_demo.launch.py

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,12 +14,19 @@ def generate_launch_description():
1414
.to_moveit_configs()
1515
)
1616

17+
sqlite_database = (
18+
get_package_share_directory("moveit2_tutorials")
19+
+ "/data/kitchen_panda_db.sqlite"
20+
)
21+
22+
print(sqlite_database)
23+
1724
## BEGIN_SUB_TUTORIAL add_config
1825
## * Add a dictionary with the warehouse_ros options
1926
warehouse_ros_config = {
2027
# For warehouse_ros_sqlite
2128
"warehouse_plugin": "warehouse_ros_sqlite::DatabaseConnection",
22-
"warehouse_host": "/path/to/my/warehouse_db.sqlite",
29+
"warehouse_host": sqlite_database,
2330
# For warehouse_ros_mongodb use the following instead
2431
# "warehouse_port": 33829,
2532
# "warehouse_host": "localhost",
@@ -133,7 +140,7 @@ def generate_launch_description():
133140
robot_state_publisher,
134141
run_move_group_node,
135142
ros2_control_node,
136-
mongodb_server_node,
143+
# mongodb_server_node,
137144
]
138145
+ load_controllers
139146
)

doc/examples/persistent_scenes_and_states/persistent_scenes_and_states.rst

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ Storage plugin selection
1818
------------------------
1919

2020
The warehouse plugin and settings have to be specified in the launch files of your MoveIt configuration.
21-
You should adapt ``move_group.launch.py`` if you do not wish to use the MongoDB plugin.
21+
You should adapt ``persistent_scenes_demo.launch.py`` if you do not wish to use the MongoDB plugin.
2222
The storage plugin is determined by the parameter ``warehouse_plugin``.
2323
Valid options are ``warehouse_ros_mongo::MongoDatabaseConnection`` for MongoDB and
2424
``warehouse_ros_sqlite::DatabaseConnection`` for SQLite.
@@ -27,15 +27,15 @@ In case of the SQLite plugin, ``warehouse_host`` contains the path to the databa
2727
and ``warehouse_port`` is unused.
2828
If the database file does not exist yet, an empty database will be created.
2929

30-
.. tutorial-formatter:: ./move_group.launch.py
30+
.. tutorial-formatter:: ./launch/persistent_scenes_demo.launch.py
3131

3232
Connecting to the storage backend
3333
---------------------------------
3434

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

38-
ros2 launch moveit2_tutorials demo.launch.py
38+
ros2 launch moveit2_tutorials persistent_scenes_demo.launch.py
3939

4040
In RViz, navigate to the "Context" tab of the "MotionPlanning" window.
4141
Verify the connection details (host/port for MongoDB, file path for SQLite)

0 commit comments

Comments
 (0)