Nav2 Navigation Stack - rolling  main
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 
17 #include <Eigen/Dense>
18 
19 #include <string>
20 #include <vector>
21 
22 #include "gtest/gtest.h"
23 #include <geometry_msgs/msg/pose_stamped.hpp>
24 #include <geometry_msgs/msg/twist.hpp>
25 #include <nav_msgs/msg/path.hpp>
26 
27 #include <nav2_costmap_2d/cost_values.hpp>
28 #include <nav2_costmap_2d/costmap_2d.hpp>
29 #include <nav2_costmap_2d/costmap_2d_ros.hpp>
30 #include <nav2_core/goal_checker.hpp>
31 #include "tf2_ros/buffer.hpp"
32 
33 #include "nav2_mppi_controller/optimizer.hpp"
34 #include "nav2_mppi_controller/motion_models.hpp"
35 
36 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
37 
38 #include "utils.hpp"
39 
40 class RosLockGuard
41 {
42 public:
43  RosLockGuard() {rclcpp::init(0, nullptr);}
44  ~RosLockGuard() {rclcpp::shutdown();}
45 };
46 
47 RosLockGuard g_rclcpp;
48 
49 void prepareAndRunBenchmark(
50  bool consider_footprint, std::string motion_model,
51  std::vector<std::string> critics, benchmark::State & state)
52 {
53  int batch_size = 2000;
54  int time_steps = 56;
55  unsigned int path_points = 50u;
56  int iteration_count = 2;
57  double lookahead_distance = 10.0;
58 
59  TestCostmapSettings costmap_settings{};
60  auto costmap_ros = getDummyCostmapRos(costmap_settings);
61  auto costmap = costmap_ros->getCostmap();
62 
63  TestPose start_pose = costmap_settings.getCenterPose();
64  double path_step = costmap_settings.resolution;
65 
66  TestPathSettings path_settings{start_pose, path_points, path_step, path_step};
67  TestOptimizerSettings optimizer_settings{batch_size, time_steps, iteration_count,
68  lookahead_distance, motion_model, consider_footprint};
69 
70  unsigned int offset = 4;
71  unsigned int obstacle_size = offset * 2;
72 
73  unsigned char obstacle_cost = 250;
74 
75  auto [obst_x, obst_y] = costmap_settings.getCenterIJ();
76 
77  obst_x = obst_x - offset;
78  obst_y = obst_y - offset;
79  addObstacle(costmap, {obst_x, obst_y, obstacle_size, obstacle_cost});
80 
81  printInfo(optimizer_settings, path_settings, critics);
82  auto node = getDummyNode(optimizer_settings, critics);
83  std::string name = "test";
84  auto parameters_handler = std::make_unique<mppi::ParametersHandler>(node, name);
85  auto tf_buffer = std::make_shared<tf2_ros::Buffer>(node->get_clock());
86  auto optimizer = getDummyOptimizer(node, costmap_ros, tf_buffer, parameters_handler.get());
87 
88  // evalControl args
89  auto pose = getDummyPointStamped(node, start_pose);
90  auto velocity = getDummyTwist();
91  auto path = getIncrementalDummyPath(node, path_settings);
92  nav2_core::GoalChecker * dummy_goal_checker{nullptr};
93 
94  for (auto _ : state) {
95  auto [cmd, trajectory] = optimizer->evalControl(pose, velocity, path, path.poses.back().pose,
96  dummy_goal_checker);
97  }
98 }
99 
100 static void BM_DiffDrivePointFootprint(benchmark::State & state)
101 {
102  bool consider_footprint = true;
103  std::string motion_model = "DiffDrive";
104  std::vector<std::string> critics = {{"ConstraintCritic"}, {"CostCritic"}, {"GoalCritic"},
105  {"GoalAngleCritic"}, {"PathAlignCritic"}, {"PathFollowCritic"}, {"PathAngleCritic"},
106  {"PreferForwardCritic"}};
107 
108  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
109 }
110 
111 static void BM_DiffDrive(benchmark::State & state)
112 {
113  bool consider_footprint = true;
114  std::string motion_model = "DiffDrive";
115  std::vector<std::string> critics = {{"ConstraintCritic"}, {"CostCritic"}, {"GoalCritic"},
116  {"GoalAngleCritic"}, {"PathAlignCritic"}, {"PathFollowCritic"}, {"PathAngleCritic"},
117  {"PreferForwardCritic"}};
118 
119  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
120 }
121 
122 static void BM_Omni(benchmark::State & state)
123 {
124  bool consider_footprint = true;
125  std::string motion_model = "Omni";
126  std::vector<std::string> critics = {{"ConstraintCritic"}, {"CostCritic"}, {"GoalCritic"},
127  {"GoalAngleCritic"}, {"PathAlignCritic"}, {"PathFollowCritic"}, {"PathAngleCritic"},
128  {"PreferForwardCritic"}};
129 
130  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
131 }
132 
133 static void BM_Ackermann(benchmark::State & state)
134 {
135  bool consider_footprint = true;
136  std::string motion_model = "Ackermann";
137  std::vector<std::string> critics = {{"ConstraintCritic"}, {"CostCritic"}, {"GoalCritic"},
138  {"GoalAngleCritic"}, {"PathAlignCritic"}, {"PathFollowCritic"}, {"PathAngleCritic"},
139  {"PreferForwardCritic"}};
140 
141  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
142 }
143 
144 static void BM_GoalCritic(benchmark::State & state)
145 {
146  bool consider_footprint = true;
147  std::string motion_model = "Ackermann";
148  std::vector<std::string> critics = {{"GoalCritic"}};
149 
150  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
151 }
152 
153 static void BM_GoalAngleCritic(benchmark::State & state)
154 {
155  bool consider_footprint = true;
156  std::string motion_model = "Ackermann";
157  std::vector<std::string> critics = {{"GoalAngleCritic"}};
158 
159  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
160 }
161 
162 static void BM_ObstaclesCritic(benchmark::State & state)
163 {
164  bool consider_footprint = true;
165  std::string motion_model = "Ackermann";
166  std::vector<std::string> critics = {{"ObstaclesCritic"}};
167 
168  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
169 }
170 
171 static void BM_ObstaclesCriticPointFootprint(benchmark::State & state)
172 {
173  bool consider_footprint = false;
174  std::string motion_model = "Ackermann";
175  std::vector<std::string> critics = {{"ObstaclesCritic"}};
176 
177  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
178 }
179 
180 static void BM_TwilringCritic(benchmark::State & state)
181 {
182  bool consider_footprint = true;
183  std::string motion_model = "Ackermann";
184  std::vector<std::string> critics = {{"TwirlingCritic"}};
185 
186  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
187 }
188 
189 static void BM_PathFollowCritic(benchmark::State & state)
190 {
191  bool consider_footprint = true;
192  std::string motion_model = "Ackermann";
193  std::vector<std::string> critics = {{"PathFollowCritic"}};
194 
195  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
196 }
197 
198 static void BM_PathAngleCritic(benchmark::State & state)
199 {
200  bool consider_footprint = true;
201  std::string motion_model = "Ackermann";
202  std::vector<std::string> critics = {{"PathAngleCritic"}};
203 
204  prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
205 }
206 
207 BENCHMARK(BM_DiffDrivePointFootprint)->Unit(benchmark::kMillisecond);
208 BENCHMARK(BM_DiffDrive)->Unit(benchmark::kMillisecond);
209 BENCHMARK(BM_Omni)->Unit(benchmark::kMillisecond);
210 BENCHMARK(BM_Ackermann)->Unit(benchmark::kMillisecond);
211 
212 BENCHMARK(BM_GoalCritic)->Unit(benchmark::kMillisecond);
213 BENCHMARK(BM_GoalAngleCritic)->Unit(benchmark::kMillisecond);
214 BENCHMARK(BM_PathAngleCritic)->Unit(benchmark::kMillisecond);
215 BENCHMARK(BM_PathFollowCritic)->Unit(benchmark::kMillisecond);
216 BENCHMARK(BM_ObstaclesCritic)->Unit(benchmark::kMillisecond);
217 BENCHMARK(BM_ObstaclesCriticPointFootprint)->Unit(benchmark::kMillisecond);
218 BENCHMARK(BM_TwilringCritic)->Unit(benchmark::kMillisecond);
219 
220 BENCHMARK_MAIN();
Function-object for checking whether a goal has been reached.