15 #include <benchmark/benchmark.h>
17 #include <Eigen/Dense>
21 #include <geometry_msgs/msg/pose_stamped.hpp>
22 #include <geometry_msgs/msg/twist.hpp>
23 #include <nav_msgs/msg/path.hpp>
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>
30 #include "nav2_mppi_controller/motion_models.hpp"
31 #include "nav2_mppi_controller/controller.hpp"
44 void prepareAndRunBenchmark(
45 bool consider_footprint, std::string motion_model,
46 std::vector<std::string> critics, benchmark::State & state)
48 bool visualize =
false;
52 unsigned int path_points = 50u;
53 int iteration_count = 2;
54 double lookahead_distance = 10.0;
56 TestCostmapSettings costmap_settings{};
57 auto costmap_ros = getDummyCostmapRos(costmap_settings);
58 auto costmap = costmap_ros->getCostmap();
60 TestPose start_pose = costmap_settings.getCenterPose();
61 double path_step = costmap_settings.resolution;
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};
67 unsigned int offset = 4;
68 unsigned int obstacle_size = offset * 2;
70 unsigned char obstacle_cost = 250;
72 auto [obst_x, obst_y] = costmap_settings.getCenterIJ();
74 obst_x = obst_x - offset;
75 obst_y = obst_y - offset;
76 addObstacle(costmap, {obst_x, obst_y, obstacle_size, obstacle_cost});
78 printInfo(optimizer_settings, path_settings, critics);
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);
87 auto tf_buffer = std::make_shared<tf2_ros::Buffer>(node->get_clock());
88 tf_buffer->setUsingDedicatedThread(
true);
91 std::make_shared<tf2_ros::TransformBroadcaster>(node);
92 auto tf_listener = std::make_shared<tf2_ros::TransformListener>(*tf_buffer);
94 auto map_odom_broadcaster = std::async(
95 std::launch::async, sendTf,
"map",
"odom", broadcaster, node,
98 auto odom_base_link_broadcaster = std::async(
99 std::launch::async, sendTf,
"odom",
"base_link", broadcaster, node,
102 auto controller = getDummyController(node, tf_buffer, costmap_ros);
105 auto pose = getDummyPointStamped(node, start_pose);
106 auto velocity = getDummyTwist();
107 auto path = getIncrementalDummyPath(node, path_settings);
109 controller->setPlan(path);
113 for (
auto _ : state) {
114 controller->computeVelocityCommands(pose, velocity, dummy_goal_checker);
116 map_odom_broadcaster.wait();
117 odom_base_link_broadcaster.wait();
120 static void BM_DiffDrivePointFootprint(benchmark::State & state)
122 bool consider_footprint =
true;
123 std::string motion_model =
"DiffDrive";
124 std::vector<std::string> critics = {{
"GoalCritic"}, {
"GoalAngleCritic"}, {
"ObstaclesCritic"},
125 {
"PathAngleCritic"}, {
"PathFollowCritic"}, {
"PreferForwardCritic"}};
127 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
130 static void BM_DiffDrive(benchmark::State & state)
132 bool consider_footprint =
true;
133 std::string motion_model =
"DiffDrive";
134 std::vector<std::string> critics = {{
"GoalCritic"}, {
"GoalAngleCritic"}, {
"ObstaclesCritic"},
135 {
"PathAngleCritic"}, {
"PathFollowCritic"}, {
"PreferForwardCritic"}};
137 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
141 static void BM_Omni(benchmark::State & state)
143 bool consider_footprint =
true;
144 std::string motion_model =
"Omni";
145 std::vector<std::string> critics = {{
"GoalCritic"}, {
"GoalAngleCritic"}, {
"ObstaclesCritic"},
146 {
"TwirlingCritic"}, {
"PathFollowCritic"}, {
"PreferForwardCritic"}};
148 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
151 static void BM_Ackermann(benchmark::State & state)
153 bool consider_footprint =
true;
154 std::string motion_model =
"Ackermann";
155 std::vector<std::string> critics = {{
"GoalCritic"}, {
"GoalAngleCritic"}, {
"ObstaclesCritic"},
156 {
"PathAngleCritic"}, {
"PathFollowCritic"}, {
"PreferForwardCritic"}};
158 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
161 static void BM_GoalCritic(benchmark::State & state)
163 bool consider_footprint =
true;
164 std::string motion_model =
"Ackermann";
165 std::vector<std::string> critics = {{
"GoalCritic"}};
167 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
170 static void BM_GoalAngleCritic(benchmark::State & state)
172 bool consider_footprint =
true;
173 std::string motion_model =
"Ackermann";
174 std::vector<std::string> critics = {{
"GoalAngleCritic"}};
176 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
179 static void BM_ObstaclesCritic(benchmark::State & state)
181 bool consider_footprint =
true;
182 std::string motion_model =
"Ackermann";
183 std::vector<std::string> critics = {{
"ObstaclesCritic"}};
185 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
188 static void BM_ObstaclesCriticPointFootprint(benchmark::State & state)
190 bool consider_footprint =
false;
191 std::string motion_model =
"Ackermann";
192 std::vector<std::string> critics = {{
"ObstaclesCritic"}};
194 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
197 static void BM_TwilringCritic(benchmark::State & state)
199 bool consider_footprint =
true;
200 std::string motion_model =
"Ackermann";
201 std::vector<std::string> critics = {{
"TwirlingCritic"}};
203 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
206 static void BM_PathFollowCritic(benchmark::State & state)
208 bool consider_footprint =
true;
209 std::string motion_model =
"Ackermann";
210 std::vector<std::string> critics = {{
"PathFollowCritic"}};
212 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
215 static void BM_PathAngleCritic(benchmark::State & state)
217 bool consider_footprint =
true;
218 std::string motion_model =
"Ackermann";
219 std::vector<std::string> critics = {{
"PathAngleCritic"}};
221 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
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);
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);
Function-object for checking whether a goal has been reached.