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