Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
optimizer_benchmark.cpp
1 // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <benchmark/benchmark.h>
16 #include <string>
17 
18 #include "gtest/gtest.h"
19 #include <geometry_msgs/msg/pose_stamped.hpp>
20 #include <geometry_msgs/msg/twist.hpp>
21 #include <nav_msgs/msg/path.hpp>
22 
23 #include <nav2_costmap_2d/cost_values.hpp>
24 #include <nav2_costmap_2d/costmap_2d.hpp>
25 #include <nav2_costmap_2d/costmap_2d_ros.hpp>
26 #include <nav2_core/goal_checker.hpp>
27 
28 #include <xtensor/xarray.hpp>
29 #include <xtensor/xio.hpp>
30 #include <xtensor/xview.hpp>
31 
32 #include "nav2_mppi_controller/optimizer.hpp"
33 #include "nav2_mppi_controller/motion_models.hpp"
34 
35 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
36 
37 #include "utils.hpp"
38 
39 class RosLockGuard
40 {
41 public:
42  RosLockGuard() {rclcpp::init(0, nullptr);}
43  ~RosLockGuard() {rclcpp::shutdown();}
44 };
45 
46 RosLockGuard g_rclcpp;
47 
48 void prepareAndRunBenchmark(
49  bool consider_footprint, std::string motion_model,
50  std::vector<std::string> critics, benchmark::State & state)
51 {
52  int batch_size = 300;
53  int time_steps = 12;
54  unsigned int path_points = 50u;
55  int iteration_count = 2;
56  double lookahead_distance = 10.0;
57 
58  TestCostmapSettings costmap_settings{};
59  auto costmap_ros = getDummyCostmapRos(costmap_settings);
60  auto costmap = costmap_ros->getCostmap();
61 
62  TestPose start_pose = costmap_settings.getCenterPose();
63  double path_step = costmap_settings.resolution;
64 
65  TestPathSettings path_settings{start_pose, path_points, path_step, path_step};
66  TestOptimizerSettings optimizer_settings{batch_size, time_steps, iteration_count,
67  lookahead_distance, motion_model, consider_footprint};
68 
69  unsigned int offset = 4;
70  unsigned int obstacle_size = offset * 2;
71 
72  unsigned char obstacle_cost = 250;
73 
74  auto [obst_x, obst_y] = costmap_settings.getCenterIJ();
75 
76  obst_x = obst_x - offset;
77  obst_y = obst_y - offset;
78  addObstacle(costmap, {obst_x, obst_y, obstacle_size, obstacle_cost});
79 
80  printInfo(optimizer_settings, path_settings, critics);
81  auto node = getDummyNode(optimizer_settings, critics);
82  auto parameters_handler = std::make_unique<mppi::ParametersHandler>(node);
83  auto optimizer = getDummyOptimizer(node, costmap_ros, parameters_handler.get());
84 
85  // evalControl args
86  auto pose = getDummyPointStamped(node, start_pose);
87  auto velocity = getDummyTwist();
88  auto path = getIncrementalDummyPath(node, path_settings);
89  nav2_core::GoalChecker * dummy_goal_checker{nullptr};
90 
91  for (auto _ : state) {
92  optimizer->evalControl(pose, velocity, path, dummy_goal_checker);
93  }
94 }
95 
96 static void BM_DiffDrivePointFootprint(benchmark::State & state)
97 {
98  bool consider_footprint = true;
99  std::string motion_model = "DiffDrive";
100  std::vector<std::string> critics = {{"GoalCritic"}, {"GoalAngleCritic"}, {"ObstaclesCritic"},
101  {"PathAngleCritic"}, {"PathFollowCritic"}, {"PreferForwardCritic"}};
102 
103  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
104 }
105 
106 static void BM_DiffDrive(benchmark::State & state)
107 {
108  bool consider_footprint = true;
109  std::string motion_model = "DiffDrive";
110  std::vector<std::string> critics = {{"GoalCritic"}, {"GoalAngleCritic"}, {"ObstaclesCritic"},
111  {"PathAngleCritic"}, {"PathFollowCritic"}, {"PreferForwardCritic"}};
112 
113  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
114 }
115 
116 
117 static void BM_Omni(benchmark::State & state)
118 {
119  bool consider_footprint = true;
120  std::string motion_model = "Omni";
121  std::vector<std::string> critics = {{"GoalCritic"}, {"GoalAngleCritic"}, {"ObstaclesCritic"},
122  {"TwirlingCritic"}, {"PathFollowCritic"}, {"PreferForwardCritic"}};
123 
124  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
125 }
126 
127 static void BM_Ackermann(benchmark::State & state)
128 {
129  bool consider_footprint = true;
130  std::string motion_model = "Ackermann";
131  std::vector<std::string> critics = {{"GoalCritic"}, {"GoalAngleCritic"}, {"ObstaclesCritic"},
132  {"PathAngleCritic"}, {"PathFollowCritic"}, {"PreferForwardCritic"}};
133 
134  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
135 }
136 
137 static void BM_GoalCritic(benchmark::State & state)
138 {
139  bool consider_footprint = true;
140  std::string motion_model = "Ackermann";
141  std::vector<std::string> critics = {{"GoalCritic"}};
142 
143  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
144 }
145 
146 static void BM_GoalAngleCritic(benchmark::State & state)
147 {
148  bool consider_footprint = true;
149  std::string motion_model = "Ackermann";
150  std::vector<std::string> critics = {{"GoalAngleCritic"}};
151 
152  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
153 }
154 
155 static void BM_ObstaclesCritic(benchmark::State & state)
156 {
157  bool consider_footprint = true;
158  std::string motion_model = "Ackermann";
159  std::vector<std::string> critics = {{"ObstaclesCritic"}};
160 
161  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
162 }
163 
164 static void BM_ObstaclesCriticPointFootprint(benchmark::State & state)
165 {
166  bool consider_footprint = false;
167  std::string motion_model = "Ackermann";
168  std::vector<std::string> critics = {{"ObstaclesCritic"}};
169 
170  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
171 }
172 
173 static void BM_TwilringCritic(benchmark::State & state)
174 {
175  bool consider_footprint = true;
176  std::string motion_model = "Ackermann";
177  std::vector<std::string> critics = {{"TwirlingCritic"}};
178 
179  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
180 }
181 
182 static void BM_PathFollowCritic(benchmark::State & state)
183 {
184  bool consider_footprint = true;
185  std::string motion_model = "Ackermann";
186  std::vector<std::string> critics = {{"PathFollowCritic"}};
187 
188  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
189 }
190 
191 static void BM_PathAngleCritic(benchmark::State & state)
192 {
193  bool consider_footprint = true;
194  std::string motion_model = "Ackermann";
195  std::vector<std::string> critics = {{"PathAngleCritic"}};
196 
197  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
198 }
199 
200 BENCHMARK(BM_DiffDrivePointFootprint)->Unit(benchmark::kMillisecond);
201 BENCHMARK(BM_DiffDrive)->Unit(benchmark::kMillisecond);
202 BENCHMARK(BM_Omni)->Unit(benchmark::kMillisecond);
203 BENCHMARK(BM_Ackermann)->Unit(benchmark::kMillisecond);
204 
205 BENCHMARK(BM_GoalCritic)->Unit(benchmark::kMillisecond);
206 BENCHMARK(BM_GoalAngleCritic)->Unit(benchmark::kMillisecond);
207 BENCHMARK(BM_PathAngleCritic)->Unit(benchmark::kMillisecond);
208 BENCHMARK(BM_PathFollowCritic)->Unit(benchmark::kMillisecond);
209 BENCHMARK(BM_ObstaclesCritic)->Unit(benchmark::kMillisecond);
210 BENCHMARK(BM_ObstaclesCriticPointFootprint)->Unit(benchmark::kMillisecond);
211 BENCHMARK(BM_TwilringCritic)->Unit(benchmark::kMillisecond);
212 
213 BENCHMARK_MAIN();
Function-object for checking whether a goal has been reached.