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