Skip to content

Commit ad70c3d

Browse files
committed
Port example script for terrain_planner_benchmark
1 parent e368ef4 commit ad70c3d

File tree

7 files changed

+182
-145
lines changed

7 files changed

+182
-145
lines changed

terrain_planner/launch/test_ompl_dubins_to_circle.launch

Lines changed: 0 additions & 13 deletions
This file was deleted.
Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<launch>
3+
<arg name="visualization" default="true"/>
4+
5+
<!-- <node pkg="tf" type="static_transform_publisher" name="world_map" args="0 0 0 0 0 0 world map 10"/> -->
6+
<node pkg="terrain_planner" exec="test_ompl_dubins_to_circle" name="test_ompl_dubins_to_circle">
7+
<param name="map_path" value="$(find-pkg-share terrain_planner)/../resources/sertig.tif"/>
8+
<param name="color_file_path" value="$(find-pkg-share terrain_planner)/../resources/sertig_color.tif"/>
9+
</node>
10+
<!-- <group if="$(arg visualization)">
11+
<node type="rviz2" name="rviz2" pkg="rviz2" args="-d $(find terrain_planner)/launch/config_dubins_to_circle.rviz" />
12+
</group> -->
13+
</launch>

terrain_planner_benchmark/CMakeLists.txt

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,13 +29,19 @@ find_package(grid_map_geo REQUIRED)
2929
find_package(terrain_navigation REQUIRED)
3030
find_package(Boost REQUIRED) # Workaround for terrain_planner not exporting this correctly
3131
find_package(terrain_planner REQUIRED)
32+
find_package(geometry_msgs REQUIRED)
3233

3334
add_library(${PROJECT_NAME})
3435
add_library(${PROJECT_NAME}::${PROJECT_NAME} ALIAS ${PROJECT_NAME})
3536

3637
target_include_directories(${PROJECT_NAME}
3738
PUBLIC
3839
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
40+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
41+
)
42+
43+
target_link_libraries(${PROJECT_NAME} PUBLIC
44+
${geometry_msgs_TARGETS}
3945
)
4046

4147
add_executable(terrain_planner_benchmark_node)
@@ -45,9 +51,13 @@ add_executable(test_rrt_replanning_node EXCLUDE_FROM_ALL)
4551
add_executable(surface_visualization EXCLUDE_FROM_ALL)
4652
add_executable(test_dubins_classification EXCLUDE_FROM_ALL)
4753
add_executable(run_replay EXCLUDE_FROM_ALL)
48-
add_executable(test_rrt_circle_goal EXCLUDE_FROM_ALL)
54+
add_executable(test_rrt_circle_goal)
4955
add_subdirectory(src)
5056

57+
target_link_libraries(test_rrt_circle_goal PUBLIC
58+
${PROJECT_NAME}
59+
)
60+
5161
include(GNUInstallDirs)
5262
install(
5363
TARGETS

terrain_planner_benchmark/launch/test_ompl_rrt_circle.launch

Lines changed: 0 additions & 17 deletions
This file was deleted.
Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<launch>
3+
<!-- <node pkg="turtlesim" exec="turtlesim_node" name="sim" namespace="turtlesim1" />
4+
<node pkg="turtlesim" exec="turtlesim_node" name="sim" namespace="turtlesim2" />
5+
<node pkg="turtlesim" exec="mimic" name="mimic">
6+
<remap from="/input/pose" to="/turtlesim1/turtle1/pose" />
7+
<remap from="/output/cmd_vel" to="/turtlesim2/turtle1/cmd_vel" />
8+
</node> -->
9+
<node pkg="terrain_planner_benchmark" exec="test_rrt_circle_goal" name="rrt_planner">
10+
</node>
11+
</launch>
12+
<!-- <?xml version="1.0" encoding="UTF-8"?>
13+
<launch>
14+
<arg name="visualization" default="true"/>
15+
<arg name="location" default="gotthard"/>
16+
17+
<node pkg="tf" type="static_transform_publisher" name="world_map" args="0 0 0 0 0 0 world map 10"/>
18+
19+
<group if="$(arg visualization)">
20+
<node type="rviz" name="rviz" pkg="rviz" args="-d $(find terrain_planner)/launch/config_ompl.rviz" />
21+
</group>
22+
</launch> -->

terrain_planner_benchmark/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
<build_depend>terrain_navigation</build_depend>
2626
<build_depend>ompl</build_depend>
2727
<build_depend>terrain_planner</build_depend>
28+
<build_depend>geometry_msgs</build_depend>
2829
<exec_depend>python3-gdal</exec_depend>
2930

3031
<export>

0 commit comments

Comments
 (0)