Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
navfn_planner.hpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2018 Simbe Robotics
3 // Copyright (c) 2019 Samsung Research America
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 
17 #ifndef NAV2_NAVFN_PLANNER__NAVFN_PLANNER_HPP_
18 #define NAV2_NAVFN_PLANNER__NAVFN_PLANNER_HPP_
19 
20 #include <chrono>
21 #include <string>
22 #include <memory>
23 #include <vector>
24 
25 #include "geometry_msgs/msg/point.hpp"
26 #include "geometry_msgs/msg/pose_stamped.hpp"
27 #include "nav2_core/global_planner.hpp"
28 #include "nav2_core/planner_exceptions.hpp"
29 #include "nav_msgs/msg/path.hpp"
30 #include "nav2_navfn_planner/navfn.hpp"
31 #include "nav2_util/robot_utils.hpp"
32 #include "nav2_util/lifecycle_node.hpp"
33 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
34 #include "nav2_util/geometry_utils.hpp"
35 
36 namespace nav2_navfn_planner
37 {
38 
40 {
41 public:
45  NavfnPlanner();
46 
50  ~NavfnPlanner();
51 
59  void configure(
60  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
61  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
62  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
63 
67  void cleanup() override;
68 
72  void activate() override;
73 
77  void deactivate() override;
78 
79 
87  nav_msgs::msg::Path createPlan(
88  const geometry_msgs::msg::PoseStamped & start,
89  const geometry_msgs::msg::PoseStamped & goal,
90  std::function<bool()> cancel_checker) override;
91 
92 protected:
102  bool makePlan(
103  const geometry_msgs::msg::Pose & start,
104  const geometry_msgs::msg::Pose & goal, double tolerance,
105  std::function<bool()> cancel_checker,
106  nav_msgs::msg::Path & plan);
107 
113  bool computePotential(const geometry_msgs::msg::Point & world_point);
114 
122  const geometry_msgs::msg::Pose & goal,
123  nav_msgs::msg::Path & plan);
124 
131  const geometry_msgs::msg::Pose & goal,
132  nav_msgs::msg::Path & plan);
133 
140  double getPointPotential(const geometry_msgs::msg::Point & world_point);
141 
142  // Check for a valid potential value at a given point in the world
143  // - must call computePotential first
144  // - currently unused
145  // bool validPointPotential(const geometry_msgs::msg::Point & world_point);
146  // bool validPointPotential(const geometry_msgs::msg::Point & world_point, double tolerance);
147 
154  inline double squared_distance(
155  const geometry_msgs::msg::Pose & p1,
156  const geometry_msgs::msg::Pose & p2)
157  {
158  double dx = p1.position.x - p2.position.x;
159  double dy = p1.position.y - p2.position.y;
160  return dx * dx + dy * dy;
161  }
162 
171  bool worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my);
172 
180  void mapToWorld(double mx, double my, double & wx, double & wy);
181 
187  void clearRobotCell(unsigned int mx, unsigned int my);
188 
193  bool isPlannerOutOfDate();
194 
195  // Planner based on ROS1 NavFn algorithm
196  std::unique_ptr<NavFn> planner_;
197 
198  // TF buffer
199  std::shared_ptr<tf2_ros::Buffer> tf_;
200 
201  // Clock
202  rclcpp::Clock::SharedPtr clock_;
203 
204  // Logger
205  rclcpp::Logger logger_{rclcpp::get_logger("NavfnPlanner")};
206 
207  // Global Costmap
208  nav2_costmap_2d::Costmap2D * costmap_;
209 
210  // The global frame of the costmap
211  std::string global_frame_, name_;
212 
213  // Whether or not the planner should be allowed to plan through unknown space
214  bool allow_unknown_, use_final_approach_orientation_;
215 
216  // If the goal is obstructed, the tolerance specifies how many meters the planner
217  // can relax the constraint in x and y before failing
218  double tolerance_;
219 
220  // Whether to use the astar planner or default dijkstras
221  bool use_astar_;
222 
223  // parent node weak ptr
224  rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
225 
226  // Dynamic parameters handler
227  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
228 
233  rcl_interfaces::msg::SetParametersResult
234  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
235 };
236 
237 } // namespace nav2_navfn_planner
238 
239 #endif // NAV2_NAVFN_PLANNER__NAVFN_PLANNER_HPP_
Abstract interface for global planners to adhere to with pluginlib.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
double squared_distance(const geometry_msgs::msg::Pose &p1, const geometry_msgs::msg::Pose &p2)
Compute the squared distance between two points.
double getPointPotential(const geometry_msgs::msg::Point &world_point)
Compute the potential, or navigation cost, at a given point in the world must call computePotential f...
bool computePotential(const geometry_msgs::msg::Point &world_point)
Compute the navigation function given a seed point in the world to start from.
void activate() override
Activate lifecycle node.
void mapToWorld(double mx, double my, double &wx, double &wy)
Transform a point from map to world frame.
bool makePlan(const geometry_msgs::msg::Pose &start, const geometry_msgs::msg::Pose &goal, double tolerance, std::function< bool()> cancel_checker, nav_msgs::msg::Path &plan)
Compute a plan given start and goal poses, provided in global world frame.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my)
Transform a point from world to map frame.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
Configuring plugin.
bool isPlannerOutOfDate()
Determine if a new planner object should be made.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
void clearRobotCell(unsigned int mx, unsigned int my)
Set the corresponding cell cost to be free space.
void smoothApproachToGoal(const geometry_msgs::msg::Pose &goal, nav_msgs::msg::Path &plan)
Remove artifacts at the end of the path - originated from planning on a discretized world.
void cleanup() override
Cleanup lifecycle node.
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::function< bool()> cancel_checker) override
Creating a plan from start and goal poses.
void deactivate() override
Deactivate lifecycle node.
bool getPlanFromPotential(const geometry_msgs::msg::Pose &goal, nav_msgs::msg::Path &plan)
Compute a plan to a goal from a potential - must call computePotential first.