Class NavfnPlanner

Inheritance Relationships

Base Type

  • public nav2_core::GlobalPlanner

Class Documentation

class NavfnPlanner : public nav2_core::GlobalPlanner

Public Functions

NavfnPlanner()

constructor

~NavfnPlanner()

destructor

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.

Parameters:
  • parent – Lifecycle node pointer

  • name – Name of plugin map

  • tf – Shared ptr of TF2 buffer

  • costmap_ros – Costmap2DROS object

void cleanup() override

Cleanup lifecycle node.

void activate() override

Activate lifecycle node.

void deactivate() override

Deactivate 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.

Parameters:
  • start – Start pose

  • goal – Goal pose

  • cancel_checker – Function to check if the task has been canceled

Returns:

nav_msgs::Path of the generated path

Protected Functions

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.

Parameters:
  • start – Start pose

  • goal – Goal pose

  • tolerance – Relaxation constraint in x and y

  • cancel_checker – Function to check if the task has been canceled

  • plan – Path to be computed

Returns:

true if can find the path

bool computePotential(const geometry_msgs::msg::Point &world_point)

Compute the navigation function given a seed point in the world to start from.

Parameters:

world_point – Point in world coordinate frame

Returns:

true if can compute

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.

Parameters:
  • goal – Goal pose

  • plan – Path to be computed

Returns:

true if can compute a plan path

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.

Parameters:
  • goal – Goal pose

  • plan – Computed path

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 first.

Parameters:

world_point – Point in world coordinate frame

Returns:

double point potential (navigation cost)

inline double squared_distance(const geometry_msgs::msg::Pose &p1, const geometry_msgs::msg::Pose &p2)

Compute the squared distance between two points.

Parameters:
  • p1 – Point 1

  • p2 – Point 2

Returns:

double squared distance between two points

bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my)

Transform a point from world to map frame.

Parameters:
  • wx – double of world X coordinate

  • wy – double of world Y coordinate

  • mx – int of map X coordinate

  • my – int of map Y coordinate

Returns:

true if can transform

void mapToWorld(double mx, double my, double &wx, double &wy)

Transform a point from map to world frame.

Parameters:
  • mx – double of map X coordinate

  • my – double of map Y coordinate

  • wx – double of world X coordinate

  • wy – double of world Y coordinate

void clearRobotCell(unsigned int mx, unsigned int my)

Set the corresponding cell cost to be free space.

Parameters:
  • mx – int of map X coordinate

  • my – int of map Y coordinate

bool isPlannerOutOfDate()

Determine if a new planner object should be made.

Returns:

true if planner object is out of date

rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)

Callback executed when a paramter change is detected.

Parameters:

parameters – list of changed parameters

Protected Attributes

std::unique_ptr<NavFn> planner_
std::shared_ptr<tf2_ros::Buffer> tf_
rclcpp::Clock::SharedPtr clock_
rclcpp::Logger logger_ = {rclcpp::get_logger("NavfnPlanner")}
nav2_costmap_2d::Costmap2D *costmap_
std::string global_frame_
std::string name_
bool allow_unknown_
bool use_final_approach_orientation_
double tolerance_
bool use_astar_
rclcpp_lifecycle::LifecycleNode::WeakPtr node_
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_