Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
planner_tester.cpp
1 // Copyright (c) 2018 Intel Corporation
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. Reserved.
14 
15 #include <string>
16 #include <random>
17 #include <tuple>
18 #include <utility>
19 #include <vector>
20 #include <memory>
21 #include <iostream>
22 #include <chrono>
23 #include <sstream>
24 #include <iomanip>
25 
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"
31 
32 using namespace std::chrono_literals;
33 using namespace std::chrono; // NOLINT
34 using nav2_util::Costmap;
35 using nav2_util::TestCostmap;
36 
37 namespace nav2_system_tests
38 {
39 
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)
47 {
48 }
49 
50 void PlannerTester::activate()
51 {
52  if (is_active_) {
53  throw std::runtime_error("Trying to activate while already active");
54  return;
55  }
56  is_active_ = true;
57 
58  // Launch a thread to process the messages for this node
59  spin_thread_ = std::make_unique<nav2_util::NodeThread>(this);
60 
61  // We start with a 10x10 grid with no obstacles
62  costmap_ = std::make_unique<Costmap>(this);
63  loadSimpleCostmap(TestCostmap::open_space);
64 
65  startRobotTransform();
66 
67  // The navfn wrapper
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");
80  rclcpp::Rate r(1);
81  r.sleep();
82  planner_tester_->onActivate(state);
83 }
84 
85 void PlannerTester::deactivate()
86 {
87  if (!is_active_) {
88  throw std::runtime_error("Trying to deactivate while already inactive");
89  return;
90  }
91  is_active_ = false;
92 
93  spin_thread_.reset();
94 
95  auto state = rclcpp_lifecycle::State();
96  planner_tester_->onDeactivate(state);
97  planner_tester_->onCleanup(state);
98 
99  map_timer_.reset();
100  map_pub_.reset();
101  map_.reset();
102  tf_broadcaster_.reset();
103 }
104 
105 PlannerTester::~PlannerTester()
106 {
107  if (is_active_) {
108  deactivate();
109  }
110 }
111 
112 void PlannerTester::startRobotTransform()
113 {
114  // Provide the robot pose transform
115  tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(this);
116 
117  // Set an initial pose
118  geometry_msgs::msg::Point robot_position;
119  robot_position.x = 1.0;
120  robot_position.y = 1.0;
121  updateRobotPosition(robot_position);
122 
123  // Publish the transform periodically
124  transform_timer_ = create_wall_timer(
125  100ms, std::bind(&PlannerTester::publishRobotTransform, this));
126 }
127 
128 void PlannerTester::updateRobotPosition(const geometry_msgs::msg::Point & position)
129 {
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";
134  }
135  std::cout << now().nanoseconds() << std::endl;
136 
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;
141 
142  publishRobotTransform();
143 }
144 
145 void PlannerTester::publishRobotTransform()
146 {
147  if (base_transform_) {
148  tf_broadcaster_->sendTransform(*base_transform_);
149  }
150 }
151 
152 void PlannerTester::loadDefaultMap()
153 {
154  // Specs for the default map
155  double resolution = 1.0;
156  bool negate = false;
157  double occupancy_threshold = 0.65;
158  double free_threshold = 0.196;
159 
160  // Define origin offset
161  std::vector<double> origin = {0.0, 0.0, 0.0};
162 
163  nav2_map_server::MapMode mode = nav2_map_server::MapMode::Trinary;
164 
165  std::string file_path = "";
166  char const * path = getenv("TEST_MAP");
167  if (path == NULL) {
168  throw std::runtime_error(
169  "Path to map image file"
170  " has not been specified in environment variable `TEST_MAP`.");
171  } else {
172  file_path = std::string(path);
173  }
174 
175  RCLCPP_INFO(this->get_logger(), "Loading map with file_path: %s", file_path.c_str());
176 
177  try {
178  map_ = std::make_shared<nav_msgs::msg::OccupancyGrid>();
179 
180  nav2_map_server::LoadParameters load_parameters;
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_);
189  } catch (...) {
190  RCLCPP_ERROR(
191  this->get_logger(),
192  "Failed to load image from file: %s", file_path.c_str());
193  throw;
194  }
195 
196  map_->header.stamp = this->now();
197  map_->header.frame_id = "map";
198  map_->info.map_load_time = this->now();
199 
200  // TODO(orduno): #443 replace with a latched topic
201  map_timer_ = create_wall_timer(1s, [this]() -> void {map_pub_->publish(*map_);});
202 
203  map_set_ = true;
204  costmap_set_ = false;
205  using_fake_costmap_ = false;
206 
207  setCostmap();
208 }
209 
210 void PlannerTester::loadSimpleCostmap(const TestCostmap & testCostmapType)
211 {
212  RCLCPP_INFO(get_logger(), "loadSimpleCostmap called.");
213  if (costmap_set_) {
214  RCLCPP_DEBUG(this->get_logger(), "Setting a new costmap with fake values");
215  }
216 
217  costmap_->set_test_costmap(testCostmapType);
218 
219  costmap_set_ = true;
220  using_fake_costmap_ = true;
221 }
222 
223 void PlannerTester::setCostmap()
224 {
225  if (!map_set_) {
226  RCLCPP_ERROR(this->get_logger(), "Map has not been provided");
227  return;
228  }
229 
230  costmap_ = std::make_unique<Costmap>(
231  this, trinary_costmap_, track_unknown_space_, lethal_threshold_, unknown_cost_value_);
232 
233  costmap_->set_static_map(*map_);
234 
235  costmap_set_ = true;
236  using_fake_costmap_ = false;
237 }
238 
239 bool PlannerTester::defaultPlannerTest(
240  ComputePathToPoseResult & path,
241  const double /*deviation_tolerance*/)
242 {
243  if (!costmap_set_) {
244  RCLCPP_ERROR(this->get_logger(), "Costmap must be set before requesting a plan");
245  return false;
246  }
247 
248  // TODO(orduno) #443 Add support for planners that take into account robot orientation
249  geometry_msgs::msg::Point robot_position;
250  ComputePathToPoseCommand goal;
251  auto costmap_properties = costmap_->get_properties();
252 
253  if (using_fake_costmap_) {
254  RCLCPP_DEBUG(this->get_logger(), "Planning using a fake costmap");
255 
256  robot_position.x = 1.0;
257  robot_position.y = 1.0;
258 
259  goal.pose.position.x = 8.0;
260  goal.pose.position.y = 8.0;
261 
262  } else {
263  RCLCPP_DEBUG(this->get_logger(), "Planning using the provided map");
264 
265  // Defined with respect to world coordinate system
266  // Planner will do coordinate transformation to map internally
267  robot_position.x = 390.0;
268  robot_position.y = 10.0;
269 
270  goal.pose.position.x = 10.0;
271  goal.pose.position.y = 390.0;
272  }
273 
274  // TODO(orduno): #443 On a default test, provide the reference path to compare with the planner
275  // result.
276  return plannerTest(robot_position, goal, path);
277 }
278 
279 bool PlannerTester::defaultPlannerRandomTests(
280  const unsigned int number_tests,
281  const float acceptable_fail_ratio = 0.1)
282 {
283  if (!costmap_set_) {
284  RCLCPP_ERROR(this->get_logger(), "Costmap must be set before requesting a plan");
285  return false;
286  }
287 
288  if (using_fake_costmap_) {
289  RCLCPP_ERROR(
290  this->get_logger(),
291  "Randomized testing with hardcoded costmaps not implemented yet");
292  return false;
293  }
294 
295  // Initialize random number generator
296  std::random_device random_device;
297  std::mt19937 generator(random_device());
298 
299  // Obtain random positions within map
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);
302 
303  auto generate_random = [&]() mutable -> std::pair<int, int> {
304  bool point_is_free = false;
305  int x, y;
306  while (!point_is_free) {
307  x = distribution_x(generator);
308  y = distribution_y(generator);
309  point_is_free = costmap_->is_free(x, y);
310  }
311  return std::make_pair(x, y);
312  };
313 
314  // TODO(orduno) #443 Add support for planners that take into account robot orientation
315  geometry_msgs::msg::Point robot_position;
316  ComputePathToPoseCommand goal;
317  ComputePathToPoseResult path;
318 
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);
323 
324  // Compose the robot start position and goal using random numbers
325  // Defined with respect to world coordinate system
326  // Planner will do coordinate transformation to map internally
327 
328  auto vals = generate_random();
329  robot_position.x = vals.first;
330  robot_position.y = vals.second;
331 
332  vals = generate_random();
333  goal.pose.position.x = vals.first;
334  goal.pose.position.y = vals.second;
335 
336  if (!plannerTest(robot_position, goal, path)) {
337  RCLCPP_WARN(
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);
340  ++num_fail;
341  }
342  }
343  auto end = high_resolution_clock::now();
344  auto elapsed = duration_cast<milliseconds>(end - start);
345 
346  RCLCPP_INFO(
347  this->get_logger(),
348  "Tested with %u tests. Planner failed on %u. Test time %ld ms",
349  number_tests, num_fail, elapsed.count());
350 
351  if ((num_fail / number_tests) > acceptable_fail_ratio) {
352  return false;
353  }
354 
355  return true;
356 }
357 
358 bool PlannerTester::plannerTest(
359  const geometry_msgs::msg::Point & robot_position,
360  const ComputePathToPoseCommand & goal,
361  ComputePathToPoseResult & path)
362 {
363  RCLCPP_DEBUG(this->get_logger(), "Getting the path from the planner");
364 
365  // First make available the current robot position for the planner to take as starting point
366  updateRobotPosition(robot_position);
367  sleep(0.05);
368 
369  // Then request to compute a path
370  TaskStatus status = createPlan(goal, path);
371 
372  RCLCPP_DEBUG(this->get_logger(), "Path request status: %d", static_cast<int8_t>(status));
373 
374  if (status == TaskStatus::FAILED) {
375  return false;
376  } else if (status == TaskStatus::SUCCEEDED) {
377  // TODO(orduno): #443 check why task may report success while planner returns a path of 0 points
378  RCLCPP_DEBUG(this->get_logger(), "Got path, checking for possible collisions");
379  return isCollisionFree(path) && isWithinTolerance(robot_position, goal, path);
380  }
381 
382  return false;
383 }
384 
385 TaskStatus PlannerTester::createPlan(
386  const ComputePathToPoseCommand & goal,
387  ComputePathToPoseResult & path)
388 {
389  // Update the costmap of the planner to the set data
390  planner_tester_->setCostmap(costmap_.get());
391 
392  // Call planning algorithm
393  if (planner_tester_->createPath(goal, path)) {
394  return TaskStatus::SUCCEEDED;
395  }
396 
397  return TaskStatus::FAILED;
398 }
399 
400 bool PlannerTester::isPathValid(nav_msgs::msg::Path & path)
401 {
402  planner_tester_->setCostmap(costmap_.get());
403  // create a fake service request
404  auto request = std::make_shared<nav2_msgs::srv::IsPathValid::Request>();
405  request->path = path;
406  auto result = path_valid_client_->async_send_request(request);
407 
408  RCLCPP_INFO(this->get_logger(), "Waiting for service complete");
409  if (rclcpp::spin_until_future_complete(
410  this->planner_tester_, result,
411  std::chrono::milliseconds(100)) ==
412  rclcpp::FutureReturnCode::SUCCESS)
413  {
414  return result.get()->is_valid;
415  } else {
416  RCLCPP_INFO(get_logger(), "Failed to call is_path_valid service");
417  return false;
418  }
419 }
420 
421 bool PlannerTester::isCollisionFree(const ComputePathToPoseResult & path)
422 {
423  // At each point of the path, check if the corresponding cell is free
424 
425  // TODO(orduno): #443 for now we are assuming the robot is the size of a single cell
426  // costmap/world_model has consider the robot footprint
427 
428  // TODO(orduno): #443 Tweak criteria for defining if a path goes into obstacles.
429  // Current navfn planner will sometimes produce paths that cut corners
430  // i.e. some points are around the corner are actually inside the obstacle
431 
432  bool collisionFree = true;
433 
434  for (auto pose : path.poses) {
435  collisionFree = costmap_->is_free(
436  static_cast<unsigned int>(std::round(pose.pose.position.x)),
437  static_cast<unsigned int>(std::round(pose.pose.position.y)));
438 
439  if (!collisionFree) {
440  RCLCPP_WARN(
441  this->get_logger(), "Path has collision at (%.2f, %.2f)",
442  pose.pose.position.x, pose.pose.position.y);
443  printPath(path);
444  return false;
445  }
446  }
447 
448  RCLCPP_DEBUG(this->get_logger(), "Path has no collisions");
449  return true;
450 }
451 
452 bool PlannerTester::isWithinTolerance(
453  const geometry_msgs::msg::Point & robot_position,
454  const ComputePathToPoseCommand & goal,
455  const ComputePathToPoseResult & path) const
456 {
457  return isWithinTolerance(
458  robot_position, goal, path, 0.0, ComputePathToPoseResult());
459 }
460 
461 bool PlannerTester::isWithinTolerance(
462  const geometry_msgs::msg::Point & robot_position,
463  const ComputePathToPoseCommand & goal,
464  const ComputePathToPoseResult & path,
465  const double /*deviationTolerance*/,
466  const ComputePathToPoseResult & /*reference_path*/) const
467 {
468  // TODO(orduno) #443 Work in progress, for now we only check that the path start matches the
469  // robot start location and that the path end matches the goal.
470 
471  auto path_start = path.poses[0];
472  auto path_end = path.poses.end()[-1];
473 
474  if (
475  path_start.pose.position.x == robot_position.x &&
476  path_start.pose.position.y == robot_position.y &&
477  path_end.pose.position.x == goal.pose.position.x &&
478  path_end.pose.position.y == goal.pose.position.y)
479  {
480  RCLCPP_DEBUG(this->get_logger(), "Path has correct start and end points");
481 
482  return true;
483  }
484  RCLCPP_WARN(this->get_logger(), "Path deviates from requested start and end points");
485 
486  RCLCPP_DEBUG(
487  this->get_logger(), "Requested path starts at (%.2f, %.2f) and ends at (%.2f, %.2f)",
488  robot_position.x, robot_position.y, goal.pose.position.x, goal.pose.position.y);
489 
490  RCLCPP_DEBUG(
491  this->get_logger(), "Computed path starts at (%.2f, %.2f) and ends at (%.2f, %.2f)",
492  path_start.pose.position.x, path_start.pose.position.y,
493  path_end.pose.position.x, path_end.pose.position.y);
494 
495  return false;
496 }
497 
498 void PlannerTester::printPath(const ComputePathToPoseResult & path) const
499 {
500  auto index = 0;
501  auto ss = std::stringstream{};
502 
503  for (auto pose : path.poses) {
504  ss << " point #" << index << " with" <<
505  " x: " << std::setprecision(3) << pose.pose.position.x <<
506  " y: " << std::setprecision(3) << pose.pose.position.y << '\n';
507  ++index;
508  }
509 
510  RCLCPP_INFO(get_logger(), ss.str().c_str());
511 }
512 
513 } // namespace nav2_system_tests
Class for a single layered costmap initialized from an occupancy grid representing the map.
Definition: costmap.hpp:45