Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_navfn_planner::NavfnPlanner Class Reference
Inheritance diagram for nav2_navfn_planner::NavfnPlanner:
Inheritance graph
[legend]
Collaboration diagram for nav2_navfn_planner::NavfnPlanner:
Collaboration graph
[legend]

Public Member 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. More...
 
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) override
 Creating a plan from start and goal poses. More...
 
- Public Member Functions inherited from nav2_core::GlobalPlanner
virtual ~GlobalPlanner ()
 Virtual destructor.
 

Protected Member Functions

bool makePlan (const geometry_msgs::msg::Pose &start, const geometry_msgs::msg::Pose &goal, double tolerance, nav_msgs::msg::Path &plan)
 Compute a plan given start and goal poses, provided in global world frame. More...
 
bool computePotential (const geometry_msgs::msg::Point &world_point)
 Compute the navigation function given a seed point in the world to start from. More...
 
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. More...
 
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. More...
 
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. More...
 
double squared_distance (const geometry_msgs::msg::Pose &p1, const geometry_msgs::msg::Pose &p2)
 Compute the squared distance between two points. More...
 
bool worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my)
 Transform a point from world to map frame. More...
 
void mapToWorld (double mx, double my, double &wx, double &wy)
 Transform a point from map to world frame. More...
 
void clearRobotCell (unsigned int mx, unsigned int my)
 Set the corresponding cell cost to be free space. More...
 
bool isPlannerOutOfDate ()
 Determine if a new planner object should be made. More...
 
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters)
 Callback executed when a paramter change is detected. More...
 

Protected Attributes

std::unique_ptr< NavFnplanner_
 
std::shared_ptr< tf2_ros::Buffer > tf_
 
rclcpp::Clock::SharedPtr clock_
 
rclcpp::Logger logger_ {rclcpp::get_logger("NavfnPlanner")}
 
nav2_costmap_2d::Costmap2Dcostmap_
 
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_
 

Additional Inherited Members

- Public Types inherited from nav2_core::GlobalPlanner
using Ptr = std::shared_ptr< GlobalPlanner >
 

Detailed Description

Definition at line 38 of file navfn_planner.hpp.

Member Function Documentation

◆ clearRobotCell()

void nav2_navfn_planner::NavfnPlanner::clearRobotCell ( unsigned int  mx,
unsigned int  my 
)
protected

Set the corresponding cell cost to be free space.

Parameters
mxint of map X coordinate
myint of map Y coordinate

Definition at line 517 of file navfn_planner.cpp.

References nav2_costmap_2d::Costmap2D::setCost().

Referenced by makePlan().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ computePotential()

bool nav2_navfn_planner::NavfnPlanner::computePotential ( const geometry_msgs::msg::Point &  world_point)
protected

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

Parameters
world_pointPoint in world coordinate frame
Returns
true if can compute

◆ configure()

void nav2_navfn_planner::NavfnPlanner::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 
)
overridevirtual

Configuring plugin.

Parameters
parentLifecycle node pointer
nameName of plugin map
tfShared ptr of TF2 buffer
costmap_rosCostmap2DROS object

Implements nav2_core::GlobalPlanner.

Definition at line 63 of file navfn_planner.cpp.

References nav2_costmap_2d::Costmap2D::getSizeInCellsX(), and nav2_costmap_2d::Costmap2D::getSizeInCellsY().

Here is the call graph for this function:

◆ createPlan()

nav_msgs::msg::Path nav2_navfn_planner::NavfnPlanner::createPlan ( const geometry_msgs::msg::PoseStamped &  start,
const geometry_msgs::msg::PoseStamped &  goal 
)
overridevirtual

Creating a plan from start and goal poses.

Parameters
startStart pose
goalGoal pose
Returns
nav_msgs::Path of the generated path

Implements nav2_core::GlobalPlanner.

Definition at line 130 of file navfn_planner.cpp.

References nav2_costmap_2d::Costmap2D::getCost(), nav2_costmap_2d::Costmap2D::getSizeInCellsX(), nav2_costmap_2d::Costmap2D::getSizeInCellsY(), isPlannerOutOfDate(), makePlan(), and nav2_costmap_2d::Costmap2D::worldToMap().

Here is the call graph for this function:

◆ dynamicParametersCallback()

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

Callback executed when a paramter change is detected.

Parameters
parameterslist of changed parameters

Definition at line 525 of file navfn_planner.cpp.

Referenced by activate().

Here is the caller graph for this function:

◆ getPlanFromPotential()

bool nav2_navfn_planner::NavfnPlanner::getPlanFromPotential ( const geometry_msgs::msg::Pose &  goal,
nav_msgs::msg::Path &  plan 
)
protected

Compute a plan to a goal from a potential - must call computePotential first.

Parameters
goalGoal pose
planPath to be computed
Returns
true if can compute a plan path

Definition at line 371 of file navfn_planner.cpp.

References nav2_costmap_2d::Costmap2D::getSizeInCellsX(), nav2_costmap_2d::Costmap2D::getSizeInCellsY(), mapToWorld(), and worldToMap().

Referenced by makePlan().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getPointPotential()

double nav2_navfn_planner::NavfnPlanner::getPointPotential ( const geometry_msgs::msg::Point &  world_point)
protected

Compute the potential, or navigation cost, at a given point in the world must call computePotential first.

Parameters
world_pointPoint in world coordinate frame
Returns
double point potential (navigation cost)

Definition at line 437 of file navfn_planner.cpp.

References worldToMap().

Referenced by makePlan().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ isPlannerOutOfDate()

bool nav2_navfn_planner::NavfnPlanner::isPlannerOutOfDate ( )
protected

Determine if a new planner object should be made.

Returns
true if planner object is out of date

Definition at line 191 of file navfn_planner.cpp.

References nav2_costmap_2d::Costmap2D::getSizeInCellsX(), and nav2_costmap_2d::Costmap2D::getSizeInCellsY().

Referenced by createPlan().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ makePlan()

bool nav2_navfn_planner::NavfnPlanner::makePlan ( const geometry_msgs::msg::Pose &  start,
const geometry_msgs::msg::Pose &  goal,
double  tolerance,
nav_msgs::msg::Path &  plan 
)
protected

Compute a plan given start and goal poses, provided in global world frame.

Parameters
startStart pose
goalGoal pose
toleranceRelaxation constraint in x and y
planPath to be computed
Returns
true if can find the path

Definition at line 203 of file navfn_planner.cpp.

References clearRobotCell(), nav2_costmap_2d::Costmap2D::getCharMap(), getPlanFromPotential(), getPointPotential(), nav2_costmap_2d::Costmap2D::getResolution(), nav2_costmap_2d::Costmap2D::getSizeInCellsX(), nav2_costmap_2d::Costmap2D::getSizeInCellsY(), smoothApproachToGoal(), squared_distance(), and worldToMap().

Referenced by createPlan().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ mapToWorld()

void nav2_navfn_planner::NavfnPlanner::mapToWorld ( double  mx,
double  my,
double &  wx,
double &  wy 
)
protected

Transform a point from map to world frame.

Parameters
mxdouble of map X coordinate
mydouble of map Y coordinate
wxdouble of world X coordinate
wydouble of world Y coordinate

Definition at line 510 of file navfn_planner.cpp.

References nav2_costmap_2d::Costmap2D::getOriginX(), nav2_costmap_2d::Costmap2D::getOriginY(), and nav2_costmap_2d::Costmap2D::getResolution().

Referenced by getPlanFromPotential().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ smoothApproachToGoal()

void nav2_navfn_planner::NavfnPlanner::smoothApproachToGoal ( const geometry_msgs::msg::Pose &  goal,
nav_msgs::msg::Path &  plan 
)
protected

Remove artifacts at the end of the path - originated from planning on a discretized world.

Parameters
goalGoal pose
planComputed path

Definition at line 347 of file navfn_planner.cpp.

References squared_distance().

Referenced by makePlan().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ squared_distance()

double nav2_navfn_planner::NavfnPlanner::squared_distance ( const geometry_msgs::msg::Pose &  p1,
const geometry_msgs::msg::Pose &  p2 
)
inlineprotected

Compute the squared distance between two points.

Parameters
p1Point 1
p2Point 2
Returns
double squared distance between two points

Definition at line 149 of file navfn_planner.hpp.

Referenced by makePlan(), and smoothApproachToGoal().

Here is the caller graph for this function:

◆ worldToMap()

bool nav2_navfn_planner::NavfnPlanner::worldToMap ( double  wx,
double  wy,
unsigned int &  mx,
unsigned int &  my 
)
protected

Transform a point from world to map frame.

Parameters
wxdouble of world X coordinate
wydouble of world Y coordinate
mxint of map X coordinate
myint of map Y coordinate
Returns
true if can transform

Definition at line 486 of file navfn_planner.cpp.

References nav2_costmap_2d::Costmap2D::getOriginX(), nav2_costmap_2d::Costmap2D::getOriginY(), nav2_costmap_2d::Costmap2D::getResolution(), nav2_costmap_2d::Costmap2D::getSizeInCellsX(), and nav2_costmap_2d::Costmap2D::getSizeInCellsY().

Referenced by getPlanFromPotential(), getPointPotential(), and makePlan().

Here is the call graph for this function:
Here is the caller graph for this function:

The documentation for this class was generated from the following files: