15 #include <benchmark/benchmark.h>
17 #include <Eigen/Dense>
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>
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>
32 #include "nav2_mppi_controller/optimizer.hpp"
33 #include "nav2_mppi_controller/motion_models.hpp"
35 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
48 void prepareAndRunBenchmark(
49 bool consider_footprint, std::string motion_model,
50 std::vector<std::string> critics, benchmark::State & state)
52 int batch_size = 2000;
54 unsigned int path_points = 50u;
55 int iteration_count = 2;
56 double lookahead_distance = 10.0;
58 TestCostmapSettings costmap_settings{};
59 auto costmap_ros = getDummyCostmapRos(costmap_settings);
60 auto costmap = costmap_ros->getCostmap();
62 TestPose start_pose = costmap_settings.getCenterPose();
63 double path_step = costmap_settings.resolution;
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};
69 unsigned int offset = 4;
70 unsigned int obstacle_size = offset * 2;
72 unsigned char obstacle_cost = 250;
74 auto [obst_x, obst_y] = costmap_settings.getCenterIJ();
76 obst_x = obst_x - offset;
77 obst_y = obst_y - offset;
78 addObstacle(costmap, {obst_x, obst_y, obstacle_size, obstacle_cost});
80 printInfo(optimizer_settings, path_settings, critics);
81 auto node = getDummyNode(optimizer_settings, critics);
82 std::string name =
"test";
83 auto parameters_handler = std::make_unique<mppi::ParametersHandler>(node, name);
84 auto optimizer = getDummyOptimizer(node, costmap_ros, parameters_handler.get());
87 auto pose = getDummyPointStamped(node, start_pose);
88 auto velocity = getDummyTwist();
89 auto path = getIncrementalDummyPath(node, path_settings);
92 for (
auto _ : state) {
93 optimizer->evalControl(pose, velocity, path, path.poses.back().pose, dummy_goal_checker);
97 static void BM_DiffDrivePointFootprint(benchmark::State & state)
99 bool consider_footprint =
true;
100 std::string motion_model =
"DiffDrive";
101 std::vector<std::string> critics = {{
"ConstraintCritic"}, {
"CostCritic"}, {
"GoalCritic"},
102 {
"GoalAngleCritic"}, {
"PathAlignCritic"}, {
"PathFollowCritic"}, {
"PathAngleCritic"},
103 {
"PreferForwardCritic"}};
105 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
108 static void BM_DiffDrive(benchmark::State & state)
110 bool consider_footprint =
true;
111 std::string motion_model =
"DiffDrive";
112 std::vector<std::string> critics = {{
"ConstraintCritic"}, {
"CostCritic"}, {
"GoalCritic"},
113 {
"GoalAngleCritic"}, {
"PathAlignCritic"}, {
"PathFollowCritic"}, {
"PathAngleCritic"},
114 {
"PreferForwardCritic"}};
116 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
119 static void BM_Omni(benchmark::State & state)
121 bool consider_footprint =
true;
122 std::string motion_model =
"Omni";
123 std::vector<std::string> critics = {{
"ConstraintCritic"}, {
"CostCritic"}, {
"GoalCritic"},
124 {
"GoalAngleCritic"}, {
"PathAlignCritic"}, {
"PathFollowCritic"}, {
"PathAngleCritic"},
125 {
"PreferForwardCritic"}};
127 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
130 static void BM_Ackermann(benchmark::State & state)
132 bool consider_footprint =
true;
133 std::string motion_model =
"Ackermann";
134 std::vector<std::string> critics = {{
"ConstraintCritic"}, {
"CostCritic"}, {
"GoalCritic"},
135 {
"GoalAngleCritic"}, {
"PathAlignCritic"}, {
"PathFollowCritic"}, {
"PathAngleCritic"},
136 {
"PreferForwardCritic"}};
138 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
141 static void BM_GoalCritic(benchmark::State & state)
143 bool consider_footprint =
true;
144 std::string motion_model =
"Ackermann";
145 std::vector<std::string> critics = {{
"GoalCritic"}};
147 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
150 static void BM_GoalAngleCritic(benchmark::State & state)
152 bool consider_footprint =
true;
153 std::string motion_model =
"Ackermann";
154 std::vector<std::string> critics = {{
"GoalAngleCritic"}};
156 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
159 static void BM_ObstaclesCritic(benchmark::State & state)
161 bool consider_footprint =
true;
162 std::string motion_model =
"Ackermann";
163 std::vector<std::string> critics = {{
"ObstaclesCritic"}};
165 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
168 static void BM_ObstaclesCriticPointFootprint(benchmark::State & state)
170 bool consider_footprint =
false;
171 std::string motion_model =
"Ackermann";
172 std::vector<std::string> critics = {{
"ObstaclesCritic"}};
174 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
177 static void BM_TwilringCritic(benchmark::State & state)
179 bool consider_footprint =
true;
180 std::string motion_model =
"Ackermann";
181 std::vector<std::string> critics = {{
"TwirlingCritic"}};
183 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
186 static void BM_PathFollowCritic(benchmark::State & state)
188 bool consider_footprint =
true;
189 std::string motion_model =
"Ackermann";
190 std::vector<std::string> critics = {{
"PathFollowCritic"}};
192 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
195 static void BM_PathAngleCritic(benchmark::State & state)
197 bool consider_footprint =
true;
198 std::string motion_model =
"Ackermann";
199 std::vector<std::string> critics = {{
"PathAngleCritic"}};
201 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
204 BENCHMARK(BM_DiffDrivePointFootprint)->Unit(benchmark::kMillisecond);
205 BENCHMARK(BM_DiffDrive)->Unit(benchmark::kMillisecond);
206 BENCHMARK(BM_Omni)->Unit(benchmark::kMillisecond);
207 BENCHMARK(BM_Ackermann)->Unit(benchmark::kMillisecond);
209 BENCHMARK(BM_GoalCritic)->Unit(benchmark::kMillisecond);
210 BENCHMARK(BM_GoalAngleCritic)->Unit(benchmark::kMillisecond);
211 BENCHMARK(BM_PathAngleCritic)->Unit(benchmark::kMillisecond);
212 BENCHMARK(BM_PathFollowCritic)->Unit(benchmark::kMillisecond);
213 BENCHMARK(BM_ObstaclesCritic)->Unit(benchmark::kMillisecond);
214 BENCHMARK(BM_ObstaclesCriticPointFootprint)->Unit(benchmark::kMillisecond);
215 BENCHMARK(BM_TwilringCritic)->Unit(benchmark::kMillisecond);
Function-object for checking whether a goal has been reached.