From d0c8ff9494727743a3f4fb8c76836975fa59346e Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 22 Sep 2022 14:20:57 -0700 Subject: [PATCH] add benchmark launch file + instructions (#3218) --- tools/planner_benchmarking/README.md | 30 ++++++++ tools/planner_benchmarking/metrics.py | 35 --------- .../planning_benchmark_bringup.py | 73 +++++++++++++++++++ 3 files changed, 103 insertions(+), 35 deletions(-) create mode 100644 tools/planner_benchmarking/README.md create mode 100644 tools/planner_benchmarking/planning_benchmark_bringup.py diff --git a/tools/planner_benchmarking/README.md b/tools/planner_benchmarking/README.md new file mode 100644 index 0000000000..c10e44003d --- /dev/null +++ b/tools/planner_benchmarking/README.md @@ -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) diff --git a/tools/planner_benchmarking/metrics.py b/tools/planner_benchmarking/metrics.py index 2ff98a25be..4cfcf721e3 100644 --- a/tools/planner_benchmarking/metrics.py +++ b/tools/planner_benchmarking/metrics.py @@ -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 = [] @@ -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) diff --git a/tools/planner_benchmarking/planning_benchmark_bringup.py b/tools/planner_benchmarking/planning_benchmark_bringup.py new file mode 100644 index 0000000000..e2a251405d --- /dev/null +++ b/tools/planner_benchmarking/planning_benchmark_bringup.py @@ -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()) + + ])