Program Listing for File navfn_planner.hpp
↰ Return to documentation for file (include/nav2_navfn_planner/navfn_planner.hpp
)
// Copyright (c) 2018 Intel Corporation
// Copyright (c) 2018 Simbe Robotics
// Copyright (c) 2019 Samsung Research America
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef NAV2_NAVFN_PLANNER__NAVFN_PLANNER_HPP_
#define NAV2_NAVFN_PLANNER__NAVFN_PLANNER_HPP_
#include <chrono>
#include <string>
#include <memory>
#include <vector>
#include "geometry_msgs/msg/point.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "nav2_core/global_planner.hpp"
#include "nav2_core/planner_exceptions.hpp"
#include "nav_msgs/msg/path.hpp"
#include "nav2_navfn_planner/navfn.hpp"
#include "nav2_util/robot_utils.hpp"
#include "nav2_util/lifecycle_node.hpp"
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
#include "nav2_util/geometry_utils.hpp"
namespace nav2_navfn_planner
{
class NavfnPlanner : public nav2_core::GlobalPlanner
{
public:
NavfnPlanner();
~NavfnPlanner();
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;
void cleanup() override;
void activate() override;
void deactivate() override;
nav_msgs::msg::Path createPlan(
const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal) override;
protected:
bool makePlan(
const geometry_msgs::msg::Pose & start,
const geometry_msgs::msg::Pose & goal, double tolerance,
nav_msgs::msg::Path & plan);
bool computePotential(const geometry_msgs::msg::Point & world_point);
bool getPlanFromPotential(
const geometry_msgs::msg::Pose & goal,
nav_msgs::msg::Path & plan);
void smoothApproachToGoal(
const geometry_msgs::msg::Pose & goal,
nav_msgs::msg::Path & plan);
double getPointPotential(const geometry_msgs::msg::Point & world_point);
// Check for a valid potential value at a given point in the world
// - must call computePotential first
// - currently unused
// bool validPointPotential(const geometry_msgs::msg::Point & world_point);
// bool validPointPotential(const geometry_msgs::msg::Point & world_point, double tolerance);
inline double squared_distance(
const geometry_msgs::msg::Pose & p1,
const geometry_msgs::msg::Pose & p2)
{
double dx = p1.position.x - p2.position.x;
double dy = p1.position.y - p2.position.y;
return dx * dx + dy * dy;
}
bool worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my);
void mapToWorld(double mx, double my, double & wx, double & wy);
void clearRobotCell(unsigned int mx, unsigned int my);
bool isPlannerOutOfDate();
// Planner based on ROS1 NavFn algorithm
std::unique_ptr<NavFn> planner_;
// TF buffer
std::shared_ptr<tf2_ros::Buffer> tf_;
// Clock
rclcpp::Clock::SharedPtr clock_;
// Logger
rclcpp::Logger logger_{rclcpp::get_logger("NavfnPlanner")};
// Global Costmap
nav2_costmap_2d::Costmap2D * costmap_;
// The global frame of the costmap
std::string global_frame_, name_;
// Whether or not the planner should be allowed to plan through unknown space
bool allow_unknown_, use_final_approach_orientation_;
// If the goal is obstructed, the tolerance specifies how many meters the planner
// can relax the constraint in x and y before failing
double tolerance_;
// Whether to use the astar planner or default dijkstras
bool use_astar_;
// parent node weak ptr
rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
// Dynamic parameters handler
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
rcl_interfaces::msg::SetParametersResult
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
};
} // namespace nav2_navfn_planner
#endif // NAV2_NAVFN_PLANNER__NAVFN_PLANNER_HPP_