26 #include "planner_tester.hpp"
27 #include "geometry_msgs/msg/twist.hpp"
28 #include "nav2_map_server/map_mode.hpp"
29 #include "nav2_map_server/map_io.hpp"
30 #include "nav2_msgs/msg/costmap_meta_data.hpp"
32 using namespace std::chrono_literals;
33 using namespace std::chrono;
35 using nav2_util::TestCostmap;
37 namespace nav2_system_tests
40 PlannerTester::PlannerTester()
41 : Node(
"PlannerTester"), is_active_(false),
42 map_set_(false), costmap_set_(false),
43 using_fake_costmap_(true), trinary_costmap_(true),
44 track_unknown_space_(false), lethal_threshold_(100), unknown_cost_value_(-1),
45 testCostmapType_(TestCostmap::open_space), base_transform_(nullptr),
46 map_publish_rate_(100s)
50 void PlannerTester::activate()
53 throw std::runtime_error(
"Trying to activate while already active");
59 spin_thread_ = std::make_unique<nav2_util::NodeThread>(
this);
62 costmap_ = std::make_unique<Costmap>(
this);
63 loadSimpleCostmap(TestCostmap::open_space);
65 startRobotTransform();
68 auto state = rclcpp_lifecycle::State();
69 planner_tester_ = std::make_shared<NavFnPlannerTester>();
70 planner_tester_->declare_parameter(
71 "GridBased.use_astar", rclcpp::ParameterValue(
true));
72 planner_tester_->set_parameter(
73 rclcpp::Parameter(std::string(
"GridBased.use_astar"), rclcpp::ParameterValue(
true)));
74 planner_tester_->set_parameter(
75 rclcpp::Parameter(std::string(
"expected_planner_frequency"), rclcpp::ParameterValue(-1.0)));
76 planner_tester_->onConfigure(state);
77 publishRobotTransform();
78 map_pub_ = this->create_publisher<nav_msgs::msg::OccupancyGrid>(
"map", 1);
79 path_valid_client_ = this->create_client<nav2_msgs::srv::IsPathValid>(
"is_path_valid");
82 planner_tester_->onActivate(state);
85 void PlannerTester::deactivate()
88 throw std::runtime_error(
"Trying to deactivate while already inactive");
95 auto state = rclcpp_lifecycle::State();
96 planner_tester_->onDeactivate(state);
97 planner_tester_->onCleanup(state);
102 tf_broadcaster_.reset();
105 PlannerTester::~PlannerTester()
112 void PlannerTester::startRobotTransform()
115 tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(
this);
118 geometry_msgs::msg::Point robot_position;
119 robot_position.x = 1.0;
120 robot_position.y = 1.0;
121 updateRobotPosition(robot_position);
124 transform_timer_ = create_wall_timer(
125 100ms, std::bind(&PlannerTester::publishRobotTransform,
this));
128 void PlannerTester::updateRobotPosition(
const geometry_msgs::msg::Point & position)
130 if (!base_transform_) {
131 base_transform_ = std::make_unique<geometry_msgs::msg::TransformStamped>();
132 base_transform_->header.frame_id =
"map";
133 base_transform_->child_frame_id =
"base_link";
135 std::cout << now().nanoseconds() << std::endl;
137 base_transform_->header.stamp = now() + rclcpp::Duration(0.25s);
138 base_transform_->transform.translation.x = position.x;
139 base_transform_->transform.translation.y = position.y;
140 base_transform_->transform.rotation.w = 1.0;
142 publishRobotTransform();
145 void PlannerTester::publishRobotTransform()
147 if (base_transform_) {
148 tf_broadcaster_->sendTransform(*base_transform_);
152 void PlannerTester::loadDefaultMap()
155 double resolution = 1.0;
157 double occupancy_threshold = 0.65;
158 double free_threshold = 0.196;
161 std::vector<double> origin = {0.0, 0.0, 0.0};
163 nav2_map_server::MapMode mode = nav2_map_server::MapMode::Trinary;
165 std::string file_path =
"";
166 char const * path = getenv(
"TEST_MAP");
168 throw std::runtime_error(
169 "Path to map image file"
170 " has not been specified in environment variable `TEST_MAP`.");
172 file_path = std::string(path);
175 RCLCPP_INFO(this->get_logger(),
"Loading map with file_path: %s", file_path.c_str());
178 map_ = std::make_shared<nav_msgs::msg::OccupancyGrid>();
181 load_parameters.image_file_name = file_path;
182 load_parameters.resolution = resolution;
183 load_parameters.origin = origin;
184 load_parameters.free_thresh = free_threshold;
185 load_parameters.occupied_thresh = occupancy_threshold;
186 load_parameters.mode = mode;
187 load_parameters.negate = negate;
188 loadMapFromFile(load_parameters, *map_);
192 "Failed to load image from file: %s", file_path.c_str());
196 map_->header.stamp = this->now();
197 map_->header.frame_id =
"map";
198 map_->info.map_load_time = this->now();
201 map_timer_ = create_wall_timer(1s, [
this]() ->
void {map_pub_->publish(*map_);});
204 costmap_set_ =
false;
205 using_fake_costmap_ =
false;
210 void PlannerTester::loadSimpleCostmap(
const TestCostmap & testCostmapType)
212 RCLCPP_INFO(get_logger(),
"loadSimpleCostmap called.");
214 RCLCPP_DEBUG(this->get_logger(),
"Setting a new costmap with fake values");
217 costmap_->set_test_costmap(testCostmapType);
220 using_fake_costmap_ =
true;
223 void PlannerTester::setCostmap()
226 RCLCPP_ERROR(this->get_logger(),
"Map has not been provided");
230 costmap_ = std::make_unique<Costmap>(
231 this, trinary_costmap_, track_unknown_space_, lethal_threshold_, unknown_cost_value_);
233 costmap_->set_static_map(*map_);
236 using_fake_costmap_ =
false;
239 bool PlannerTester::defaultPlannerTest(
240 ComputePathToPoseResult & path,
244 RCLCPP_ERROR(this->get_logger(),
"Costmap must be set before requesting a plan");
249 geometry_msgs::msg::Point robot_position;
250 ComputePathToPoseCommand goal;
251 auto costmap_properties = costmap_->get_properties();
253 if (using_fake_costmap_) {
254 RCLCPP_DEBUG(this->get_logger(),
"Planning using a fake costmap");
256 robot_position.x = 1.0;
257 robot_position.y = 1.0;
259 goal.pose.position.x = 8.0;
260 goal.pose.position.y = 8.0;
263 RCLCPP_DEBUG(this->get_logger(),
"Planning using the provided map");
267 robot_position.x = 390.0;
268 robot_position.y = 10.0;
270 goal.pose.position.x = 10.0;
271 goal.pose.position.y = 390.0;
276 return plannerTest(robot_position, goal, path);
279 bool PlannerTester::defaultPlannerRandomTests(
280 const unsigned int number_tests,
281 const float acceptable_fail_ratio = 0.1)
284 RCLCPP_ERROR(this->get_logger(),
"Costmap must be set before requesting a plan");
288 if (using_fake_costmap_) {
291 "Randomized testing with hardcoded costmaps not implemented yet");
296 std::random_device random_device;
297 std::mt19937 generator(random_device());
300 std::uniform_int_distribution<> distribution_x(1, costmap_->get_properties().size_x - 1);
301 std::uniform_int_distribution<> distribution_y(1, costmap_->get_properties().size_y - 1);
303 auto generate_random = [&]()
mutable -> std::pair<int, int> {
304 bool point_is_free =
false;
306 while (!point_is_free) {
307 x = distribution_x(generator);
308 y = distribution_y(generator);
309 point_is_free = costmap_->is_free(x, y);
311 return std::make_pair(x, y);
315 geometry_msgs::msg::Point robot_position;
316 ComputePathToPoseCommand goal;
317 ComputePathToPoseResult path;
319 unsigned int num_fail = 0;
320 auto start = high_resolution_clock::now();
321 for (
unsigned int test_num = 0; test_num < number_tests; ++test_num) {
322 RCLCPP_DEBUG(this->get_logger(),
"Running test #%u", test_num + 1);
328 auto vals = generate_random();
329 robot_position.x = vals.first;
330 robot_position.y = vals.second;
332 vals = generate_random();
333 goal.pose.position.x = vals.first;
334 goal.pose.position.y = vals.second;
336 if (!plannerTest(robot_position, goal, path)) {
338 this->get_logger(),
"Failed with start at %0.2f, %0.2f and goal at %0.2f, %0.2f",
339 robot_position.x, robot_position.y, goal.pose.position.x, goal.pose.position.y);
343 auto end = high_resolution_clock::now();
344 auto elapsed = duration_cast<milliseconds>(end - start);
348 "Tested with %u tests. Planner failed on %u. Test time %ld ms",
349 number_tests, num_fail, elapsed.count());
351 if ((num_fail / number_tests) > acceptable_fail_ratio) {
358 bool PlannerTester::plannerTest(
359 const geometry_msgs::msg::Point & robot_position,
360 const ComputePathToPoseCommand & goal,
361 ComputePathToPoseResult & path)
363 RCLCPP_DEBUG(this->get_logger(),
"Getting the path from the planner");
366 updateRobotPosition(robot_position);
370 TaskStatus status = createPlan(goal, path);
372 RCLCPP_DEBUG(this->get_logger(),
"Path request status: %d",
static_cast<int8_t
>(status));
374 if (status == TaskStatus::FAILED) {
376 }
else if (status == TaskStatus::SUCCEEDED) {
378 RCLCPP_DEBUG(this->get_logger(),
"Got path, checking for possible collisions");
379 return isCollisionFree(path) && isWithinTolerance(robot_position, goal, path);
385 TaskStatus PlannerTester::createPlan(
386 const ComputePathToPoseCommand & goal,
387 ComputePathToPoseResult & path)
390 planner_tester_->setCostmap(costmap_.get());
393 if (planner_tester_->createPath(goal, path)) {
394 return TaskStatus::SUCCEEDED;
397 return TaskStatus::FAILED;
400 bool PlannerTester::isPathValid(
401 nav_msgs::msg::Path & path,
unsigned int max_cost,
402 bool consider_unknown_as_obstacle)
404 planner_tester_->setCostmap(costmap_.get());
406 auto request = std::make_shared<nav2_msgs::srv::IsPathValid::Request>();
407 request->path = path;
408 request->max_cost = max_cost;
409 request->consider_unknown_as_obstacle = consider_unknown_as_obstacle;
410 auto result = path_valid_client_->async_send_request(request);
412 RCLCPP_INFO(this->get_logger(),
"Waiting for service complete");
413 if (rclcpp::spin_until_future_complete(
414 this->planner_tester_, result,
415 std::chrono::milliseconds(100)) ==
416 rclcpp::FutureReturnCode::SUCCESS)
418 return result.get()->is_valid;
420 RCLCPP_INFO(get_logger(),
"Failed to call is_path_valid service");
425 bool PlannerTester::isCollisionFree(
const ComputePathToPoseResult & path)
436 bool collisionFree =
true;
438 for (
auto pose : path.poses) {
439 collisionFree = costmap_->is_free(
440 static_cast<unsigned int>(std::round(pose.pose.position.x)),
441 static_cast<unsigned int>(std::round(pose.pose.position.y)));
443 if (!collisionFree) {
445 this->get_logger(),
"Path has collision at (%.2f, %.2f)",
446 pose.pose.position.x, pose.pose.position.y);
452 RCLCPP_DEBUG(this->get_logger(),
"Path has no collisions");
456 bool PlannerTester::isWithinTolerance(
457 const geometry_msgs::msg::Point & robot_position,
458 const ComputePathToPoseCommand & goal,
459 const ComputePathToPoseResult & path)
const
461 return isWithinTolerance(
462 robot_position, goal, path, 0.0, ComputePathToPoseResult());
465 bool PlannerTester::isWithinTolerance(
466 const geometry_msgs::msg::Point & robot_position,
467 const ComputePathToPoseCommand & goal,
468 const ComputePathToPoseResult & path,
470 const ComputePathToPoseResult & )
const
475 auto path_start = path.poses[0];
476 auto path_end = path.poses.end()[-1];
479 path_start.pose.position.x == robot_position.x &&
480 path_start.pose.position.y == robot_position.y &&
481 path_end.pose.position.x == goal.pose.position.x &&
482 path_end.pose.position.y == goal.pose.position.y)
484 RCLCPP_DEBUG(this->get_logger(),
"Path has correct start and end points");
488 RCLCPP_WARN(this->get_logger(),
"Path deviates from requested start and end points");
491 this->get_logger(),
"Requested path starts at (%.2f, %.2f) and ends at (%.2f, %.2f)",
492 robot_position.x, robot_position.y, goal.pose.position.x, goal.pose.position.y);
495 this->get_logger(),
"Computed path starts at (%.2f, %.2f) and ends at (%.2f, %.2f)",
496 path_start.pose.position.x, path_start.pose.position.y,
497 path_end.pose.position.x, path_end.pose.position.y);
502 void PlannerTester::printPath(
const ComputePathToPoseResult & path)
const
505 auto ss = std::stringstream{};
507 for (
auto pose : path.poses) {
508 ss <<
" point #" << index <<
" with" <<
509 " x: " << std::setprecision(3) << pose.pose.position.x <<
510 " y: " << std::setprecision(3) << pose.pose.position.y <<
'\n';
514 RCLCPP_INFO(get_logger(), ss.str().c_str());
Class for a single layered costmap initialized from an occupancy grid representing the map.