15 #include <benchmark/benchmark.h>
18 #include <geometry_msgs/msg/pose_stamped.hpp>
19 #include <geometry_msgs/msg/twist.hpp>
20 #include <nav_msgs/msg/path.hpp>
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>
27 #include <xtensor/xarray.hpp>
28 #include <xtensor/xio.hpp>
29 #include <xtensor/xview.hpp>
31 #include "nav2_mppi_controller/motion_models.hpp"
32 #include "nav2_mppi_controller/controller.hpp"
45 void prepareAndRunBenchmark(
46 bool consider_footprint, std::string motion_model,
47 std::vector<std::string> critics, benchmark::State & state)
49 bool visualize =
false;
53 unsigned int path_points = 50u;
54 int iteration_count = 2;
55 double lookahead_distance = 10.0;
57 TestCostmapSettings costmap_settings{};
58 auto costmap_ros = getDummyCostmapRos(costmap_settings);
59 auto costmap = costmap_ros->getCostmap();
61 TestPose start_pose = costmap_settings.getCenterPose();
62 double path_step = costmap_settings.resolution;
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};
68 unsigned int offset = 4;
69 unsigned int obstacle_size = offset * 2;
71 unsigned char obstacle_cost = 250;
73 auto [obst_x, obst_y] = costmap_settings.getCenterIJ();
75 obst_x = obst_x - offset;
76 obst_y = obst_y - offset;
77 addObstacle(costmap, {obst_x, obst_y, obstacle_size, obstacle_cost});
79 printInfo(optimizer_settings, path_settings, critics);
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);
88 auto tf_buffer = std::make_shared<tf2_ros::Buffer>(node->get_clock());
89 tf_buffer->setUsingDedicatedThread(
true);
92 std::make_shared<tf2_ros::TransformBroadcaster>(node);
93 auto tf_listener = std::make_shared<tf2_ros::TransformListener>(*tf_buffer);
95 auto map_odom_broadcaster = std::async(
96 std::launch::async, sendTf,
"map",
"odom", broadcaster, node,
99 auto odom_base_link_broadcaster = std::async(
100 std::launch::async, sendTf,
"odom",
"base_link", broadcaster, node,
103 auto controller = getDummyController(node, tf_buffer, costmap_ros);
106 auto pose = getDummyPointStamped(node, start_pose);
107 auto velocity = getDummyTwist();
108 auto path = getIncrementalDummyPath(node, path_settings);
110 controller->setPlan(path);
114 for (
auto _ : state) {
115 controller->computeVelocityCommands(pose, velocity, dummy_goal_checker);
117 map_odom_broadcaster.wait();
118 odom_base_link_broadcaster.wait();
121 static void BM_DiffDrivePointFootprint(benchmark::State & state)
123 bool consider_footprint =
true;
124 std::string motion_model =
"DiffDrive";
125 std::vector<std::string> critics = {{
"GoalCritic"}, {
"GoalAngleCritic"}, {
"ObstaclesCritic"},
126 {
"PathAngleCritic"}, {
"PathFollowCritic"}, {
"PreferForwardCritic"}};
128 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
131 static void BM_DiffDrive(benchmark::State & state)
133 bool consider_footprint =
true;
134 std::string motion_model =
"DiffDrive";
135 std::vector<std::string> critics = {{
"GoalCritic"}, {
"GoalAngleCritic"}, {
"ObstaclesCritic"},
136 {
"PathAngleCritic"}, {
"PathFollowCritic"}, {
"PreferForwardCritic"}};
138 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
142 static void BM_Omni(benchmark::State & state)
144 bool consider_footprint =
true;
145 std::string motion_model =
"Omni";
146 std::vector<std::string> critics = {{
"GoalCritic"}, {
"GoalAngleCritic"}, {
"ObstaclesCritic"},
147 {
"TwirlingCritic"}, {
"PathFollowCritic"}, {
"PreferForwardCritic"}};
149 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
152 static void BM_Ackermann(benchmark::State & state)
154 bool consider_footprint =
true;
155 std::string motion_model =
"Ackermann";
156 std::vector<std::string> critics = {{
"GoalCritic"}, {
"GoalAngleCritic"}, {
"ObstaclesCritic"},
157 {
"PathAngleCritic"}, {
"PathFollowCritic"}, {
"PreferForwardCritic"}};
159 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
162 static void BM_GoalCritic(benchmark::State & state)
164 bool consider_footprint =
true;
165 std::string motion_model =
"Ackermann";
166 std::vector<std::string> critics = {{
"GoalCritic"}};
168 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
171 static void BM_GoalAngleCritic(benchmark::State & state)
173 bool consider_footprint =
true;
174 std::string motion_model =
"Ackermann";
175 std::vector<std::string> critics = {{
"GoalAngleCritic"}};
177 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
180 static void BM_ObstaclesCritic(benchmark::State & state)
182 bool consider_footprint =
true;
183 std::string motion_model =
"Ackermann";
184 std::vector<std::string> critics = {{
"ObstaclesCritic"}};
186 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
189 static void BM_ObstaclesCriticPointFootprint(benchmark::State & state)
191 bool consider_footprint =
false;
192 std::string motion_model =
"Ackermann";
193 std::vector<std::string> critics = {{
"ObstaclesCritic"}};
195 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
198 static void BM_TwilringCritic(benchmark::State & state)
200 bool consider_footprint =
true;
201 std::string motion_model =
"Ackermann";
202 std::vector<std::string> critics = {{
"TwirlingCritic"}};
204 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
207 static void BM_PathFollowCritic(benchmark::State & state)
209 bool consider_footprint =
true;
210 std::string motion_model =
"Ackermann";
211 std::vector<std::string> critics = {{
"PathFollowCritic"}};
213 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
216 static void BM_PathAngleCritic(benchmark::State & state)
218 bool consider_footprint =
true;
219 std::string motion_model =
"Ackermann";
220 std::vector<std::string> critics = {{
"PathAngleCritic"}};
222 prepareAndRunBenchmark(consider_footprint, motion_model, critics, state);
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);
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);
Function-object for checking whether a goal has been reached.