Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
planner_tester.hpp
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 #ifndef PLANNING__PLANNER_TESTER_HPP_
16 #define PLANNING__PLANNER_TESTER_HPP_
17 
18 #include <gtest/gtest.h>
19 #include <memory>
20 #include <string>
21 #include <thread>
22 #include <algorithm>
23 
24 #include "rclcpp/rclcpp.hpp"
25 #include "nav2_msgs/action/compute_path_to_pose.hpp"
26 #include "nav_msgs/msg/occupancy_grid.hpp"
27 #include "nav2_msgs/msg/costmap.hpp"
28 #include "nav2_msgs/srv/get_costmap.hpp"
29 #include "nav2_msgs/srv/is_path_valid.hpp"
30 #include "nav2_util/costmap.hpp"
31 #include "nav2_util/node_thread.hpp"
32 #include "geometry_msgs/msg/pose_stamped.hpp"
33 #include "geometry_msgs/msg/transform_stamped.hpp"
34 #include "nav2_planner/planner_server.hpp"
35 #include "tf2_ros/transform_broadcaster.h"
36 
37 namespace nav2_system_tests
38 {
39 
41 {
42 public:
44  : PlannerServer()
45  {
46  }
47 
48  void printCostmap()
49  {
50  // print costmap for debug
51  for (size_t i = 0; i != costmap_->getSizeInCellsX() * costmap_->getSizeInCellsY(); i++) {
52  if (i % costmap_->getSizeInCellsX() == 0) {
53  std::cout << "" << std::endl;
54  }
55  std::cout << costmap_ros_->getCostmap()->getCharMap()[i] << " ";
56  }
57  std::cout << "" << std::endl;
58  }
59 
60  void setCostmap(nav2_util::Costmap * costmap)
61  {
62  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(
63  *(costmap_ros_->getCostmap()->getMutex()));
64 
65  nav2_msgs::msg::CostmapMetaData prop;
66  nav2_msgs::msg::Costmap cm = costmap->get_costmap(prop);
67  prop = cm.metadata;
68  costmap_ros_->getCostmap()->resizeMap(
69  prop.size_x, prop.size_y,
70  prop.resolution, prop.origin.position.x, prop.origin.position.x);
71  // Volatile prevents compiler from treating costmap_ptr as unused or changing its address
72  volatile unsigned char * costmap_ptr = costmap_ros_->getCostmap()->getCharMap();
73  delete[] costmap_ptr;
74  costmap_ptr = new unsigned char[prop.size_x * prop.size_y];
75  std::copy(cm.data.begin(), cm.data.end(), costmap_ptr);
76  }
77 
78  bool createPath(
79  const geometry_msgs::msg::PoseStamped & goal,
80  nav_msgs::msg::Path & path)
81  {
82  geometry_msgs::msg::PoseStamped start;
83  if (!nav2_util::getCurrentPose(start, *tf_, "map", "base_link", 0.1)) {
84  return false;
85  }
86  try {
87  auto dummy_cancel_checker = []() {return false;};
88  path = planners_["GridBased"]->createPlan(start, goal, dummy_cancel_checker);
89  // The situation when createPlan() did not throw any exception
90  // does not guarantee that plan was created correctly.
91  // So it should be checked additionally that path is correct.
92  if (!path.poses.size()) {
93  return false;
94  }
95  } catch (...) {
96  return false;
97  }
98  return true;
99  }
100 
101  void onCleanup(const rclcpp_lifecycle::State & state)
102  {
103  on_cleanup(state);
104  }
105 
106  void onActivate(const rclcpp_lifecycle::State & state)
107  {
108  on_activate(state);
109  }
110 
111  void onDeactivate(const rclcpp_lifecycle::State & state)
112  {
113  on_deactivate(state);
114  }
115 
116  void onConfigure(const rclcpp_lifecycle::State & state)
117  {
118  on_configure(state);
119  }
120 };
121 
122 enum class TaskStatus : int8_t
123 {
124  SUCCEEDED = 1,
125  FAILED = 2,
126  RUNNING = 3,
127 };
128 
129 class PlannerTester : public rclcpp::Node
130 {
131 public:
132  using ComputePathToPoseCommand = geometry_msgs::msg::PoseStamped;
133  using ComputePathToPoseResult = nav_msgs::msg::Path;
134 
135  PlannerTester();
136  ~PlannerTester();
137 
138  // Activate the tester before running tests
139  void activate();
140  void deactivate();
141 
142  // Loads the provided map and and generates a costmap from it.
143  void loadDefaultMap();
144 
145  // Alternatively, use a preloaded 10x10 costmap
146  void loadSimpleCostmap(const nav2_util::TestCostmap & testCostmapType);
147 
148  // Runs a single test with default poses depending on the loaded map
149  // Success criteria is a collision free path and a deviation to a
150  // reference path smaller than a tolerance.
151  bool defaultPlannerTest(
152  ComputePathToPoseResult & path,
153  const double deviation_tolerance = 1.0);
154 
155 
156  // Runs multiple tests with random initial and goal poses
157  bool defaultPlannerRandomTests(
158  const unsigned int number_tests,
159  const float acceptable_fail_ratio);
160 
161  bool isPathValid(
162  nav_msgs::msg::Path & path, unsigned int max_cost,
163  bool consider_unknown_as_obstacle);
164 
165 private:
166  void setCostmap();
167 
168  TaskStatus createPlan(
169  const ComputePathToPoseCommand & goal,
170  ComputePathToPoseResult & path
171  );
172 
173  bool is_active_;
174  bool map_set_;
175  bool costmap_set_;
176  bool using_fake_costmap_;
177 
178  // Parameters of the costmap
179  bool trinary_costmap_;
180  bool track_unknown_space_;
181  int lethal_threshold_;
182  int unknown_cost_value_;
183  nav2_util::TestCostmap testCostmapType_;
184 
185  // The static map
186  std::shared_ptr<nav_msgs::msg::OccupancyGrid> map_;
187 
188  // The costmap representation of the static map
189  std::unique_ptr<nav2_util::Costmap> costmap_;
190 
191  // The global planner
192  std::shared_ptr<NavFnPlannerTester> planner_tester_;
193 
194  // The is path valid client
195  rclcpp::Client<nav2_msgs::srv::IsPathValid>::SharedPtr path_valid_client_;
196 
197  // A thread for spinning the ROS node
198  std::unique_ptr<nav2_util::NodeThread> spin_thread_;
199 
200  // The tester must provide the robot pose through a transform
201  std::unique_ptr<geometry_msgs::msg::TransformStamped> base_transform_;
202  std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
203  rclcpp::TimerBase::SharedPtr transform_timer_;
204  void publishRobotTransform();
205  void startRobotTransform();
206  void updateRobotPosition(const geometry_msgs::msg::Point & position);
207 
208  // Occupancy grid publisher for visualization
209  rclcpp::Publisher<nav_msgs::msg::OccupancyGrid>::SharedPtr map_pub_;
210  rclcpp::TimerBase::SharedPtr map_timer_;
211  rclcpp::WallRate map_publish_rate_;
212  void mapCallback();
213 
214  // Executes a test run with the provided end points.
215  // Success criteria is a collision free path.
216  // TODO(orduno): #443 Assuming a robot the size of a costmap cell
217  bool plannerTest(
218  const geometry_msgs::msg::Point & robot_position,
219  const ComputePathToPoseCommand & goal,
220  ComputePathToPoseResult & path);
221 
222  bool isCollisionFree(const ComputePathToPoseResult & path);
223 
224  bool isWithinTolerance(
225  const geometry_msgs::msg::Point & robot_position,
226  const ComputePathToPoseCommand & goal,
227  const ComputePathToPoseResult & path) const;
228 
229  bool isWithinTolerance(
230  const geometry_msgs::msg::Point & robot_position,
231  const ComputePathToPoseCommand & goal,
232  const ComputePathToPoseResult & path,
233  const double deviationTolerance,
234  const ComputePathToPoseResult & reference_path) const;
235 
236  void printPath(const ComputePathToPoseResult & path) const;
237 };
238 
239 } // namespace nav2_system_tests
240 
241 #endif // PLANNING__PLANNER_TESTER_HPP_
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:551
An action server implements the behavior tree's ComputePathToPose interface and hosts various plugins...
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Reset member variables.
PlannerServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_planner::PlannerServer.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure member variables and initializes planner.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate member variables.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate member variables.
Class for a single layered costmap initialized from an occupancy grid representing the map.
Definition: costmap.hpp:45
nav2_msgs::msg::Costmap get_costmap(const nav2_msgs::msg::CostmapMetaData &specifications)
Get a costmap message from this object.
Definition: costmap.cpp:108