Skip to content

Commit

Permalink
add benchmark launch file + instructions (#3218)
Browse files Browse the repository at this point in the history
  • Loading branch information
SteveMacenski authored Sep 22, 2022
1 parent 0b4179b commit d0c8ff9
Show file tree
Hide file tree
Showing 3 changed files with 103 additions and 35 deletions.
30 changes: 30 additions & 0 deletions tools/planner_benchmarking/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
# Planning Benchmark

This experiment runs a set of planners over randomly generated maps, with randomly generated goals for objective benchmarking.

To use, modify the Nav2 bringup parameters to include the planners of interest:

```
planner_server:
ros__parameters:
expected_planner_frequency: 20.0
use_sim_time: True
planner_plugins: ["SmacHybrid", "Smac2d", "SmacLattice", "Navfn", "ThetaStar"]
SmacHybrid:
plugin: "nav2_smac_planner/SmacPlannerHybrid"
Smac2d:
plugin: "nav2_smac_planner/SmacPlanner2D"
SmacLattice:
plugin: "nav2_smac_planner/SmacPlannerLattice"
Navfn:
plugin: "nav2_navfn_planner/NavfnPlanner"
ThetaStar:
plugin: "nav2_theta_star_planner/ThetaStarPlanner"
```

Set global costmap settings to those desired for benchmarking. The global map will be automatically set in the script. Inside of `metrics.py`, you can modify the map or set of planners to use.

Launch the benchmark via `ros2 launch ./planning_benchmark_bringup.py` to launch the planner and map servers, then run each script in this directory:

- `metrics.py` to capture data in `.pickle` files.
- `process_data.py` to take the metric files and process them into key results (and plots)
35 changes: 0 additions & 35 deletions tools/planner_benchmarking/metrics.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,28 +31,6 @@

from transforms3d.euler import euler2quat

'''
Replace planner server with:
planner_server:
ros__parameters:
expected_planner_frequency: 20.0
use_sim_time: True
planner_plugins: ["SmacHybrid", "Smac2d", "SmacLattice", "Navfn", "ThetaStar"]
SmacHybrid:
plugin: "nav2_smac_planner/SmacPlannerHybrid"
Smac2d:
plugin: "nav2_smac_planner/SmacPlanner2D"
SmacLattice:
plugin: "nav2_smac_planner/SmacPlannerLattice"
Navfn:
plugin: "nav2_navfn_planner/NavfnPlanner"
ThetaStar:
plugin: "nav2_theta_star_planner/ThetaStarPlanner"
Set global costmap settings to those desired for benchmarking.
The global map will be automatically set in the script.
'''

def getPlannerResults(navigator, initial_pose, goal_pose, planners):
results = []
Expand Down Expand Up @@ -120,19 +98,6 @@ def main():

navigator = BasicNavigator()

# Set our experiment's initial pose
initial_pose = PoseStamped()
initial_pose.header.frame_id = 'map'
initial_pose.header.stamp = navigator.get_clock().now().to_msg()
initial_pose.pose.position.x = 1.0
initial_pose.pose.position.y = 1.0
initial_pose.pose.orientation.z = 0.0
initial_pose.pose.orientation.w = 1.0
navigator.setInitialPose(initial_pose)

# Wait for navigation to fully activate
navigator.waitUntilNav2Active()

# Set map to use, other options: 100by100_15, 100by100_10
map_path = os.getcwd() + '/' + glob.glob('**/100by100_20.yaml', recursive=True)[0]
navigator.changeMap(map_path)
Expand Down
73 changes: 73 additions & 0 deletions tools/planner_benchmarking/planning_benchmark_bringup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
# Copyright (c) 2022 Samsung Research America
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import os

from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory

def generate_launch_description():
nav2_bringup_dir = get_package_share_directory('nav2_bringup')
config = os.path.join(get_package_share_directory('nav2_bringup'), 'params', 'nav2_params.yaml')
map_file = os.path.join(nav2_bringup_dir, 'maps', 'map.yaml')
lifecycle_nodes = ['map_server', 'planner_server']

return LaunchDescription([
Node(
package='nav2_map_server',
executable='map_server',
name='map_server',
output='screen',
parameters=[{'use_sim_time': True},
{'yaml_filename': map_file},
{'topic_name': "map"}]),

Node(
package='nav2_planner',
executable='planner_server',
name='planner_server',
output='screen',
parameters=[config]),

Node(
package = 'tf2_ros',
executable = 'static_transform_publisher',
output = 'screen',
arguments = ["0", "0", "0", "0", "0", "0", "base_link", "map"]),

Node(
package = 'tf2_ros',
executable = 'static_transform_publisher',
output = 'screen',
arguments = ["0", "0", "0", "0", "0", "0", "base_link", "odom"]),

Node(
package='nav2_lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager',
output='screen',
parameters=[{'use_sim_time': True},
{'autostart': True},
{'node_names': lifecycle_nodes}]),

IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py')),
launch_arguments={'namespace': '',
'use_namespace': 'False'}.items())

])

0 comments on commit d0c8ff9

Please sign in to comment.