17 #ifndef NAV2_NAVFN_PLANNER__NAVFN_PLANNER_HPP_
18 #define NAV2_NAVFN_PLANNER__NAVFN_PLANNER_HPP_
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_ros_common/lifecycle_node.hpp"
33 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
34 #include "nav2_util/geometry_utils.hpp"
36 namespace nav2_navfn_planner
60 const nav2::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;
88 const geometry_msgs::msg::PoseStamped & start,
89 const geometry_msgs::msg::PoseStamped & goal,
90 std::function<
bool()> cancel_checker)
override;
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);
122 const geometry_msgs::msg::Pose & goal,
123 nav_msgs::msg::Path & plan);
131 const geometry_msgs::msg::Pose & goal,
132 nav_msgs::msg::Path & plan);
155 const geometry_msgs::msg::Pose & p1,
156 const geometry_msgs::msg::Pose & p2)
158 double dx = p1.position.x - p2.position.x;
159 double dy = p1.position.y - p2.position.y;
160 return dx * dx + dy * dy;
171 bool worldToMap(
double wx,
double wy,
unsigned int & mx,
unsigned int & my);
180 void mapToWorld(
double mx,
double my,
double & wx,
double & wy);
196 std::unique_ptr<NavFn> planner_;
199 std::shared_ptr<tf2_ros::Buffer> tf_;
202 rclcpp::Clock::SharedPtr clock_;
205 rclcpp::Logger logger_{rclcpp::get_logger(
"NavfnPlanner")};
211 std::string global_frame_, name_;
214 bool allow_unknown_, use_final_approach_orientation_;
224 nav2::LifecycleNode::WeakPtr node_;
227 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
233 rcl_interfaces::msg::SetParametersResult
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".
double squared_distance(const geometry_msgs::msg::Pose &p1, const geometry_msgs::msg::Pose &p2)
Compute the squared distance between two points.
~NavfnPlanner()
destructor
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.
bool isPlannerOutOfDate()
Determine if a new planner object should be made.
void configure(const nav2::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.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter 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.
NavfnPlanner()
constructor
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.