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