Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
navfn::NavfnROS Class Reference

Provides a ROS wrapper for the navfn planner which runs a fast, interpolated navigation function on a costmap. More...

#include <navfn_ros.h>

Inheritance diagram for navfn::NavfnROS:
Inheritance graph
[legend]

Public Member Functions

bool computePotential (const geometry_msgs::Point &world_point)
 Computes the full navigation function for the map given a point in the world to start from. More...
 
bool getPlanFromPotential (const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
 Compute a plan to a goal after the potential for a start point has already been computed (Note: You should call computePotential first) More...
 
double getPointPotential (const geometry_msgs::Point &world_point)
 Get the potential, or naviagation cost, at a given point in the world (Note: You should call computePotential first) More...
 
void initialize (std::string name, costmap_2d::Costmap2D *costmap, std::string global_frame)
 Initialization function for the NavFnROS object. More...
 
void initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
 Initialization function for the NavFnROS object. More...
 
bool makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, std::vector< geometry_msgs::PoseStamped > &plan)
 Given a goal pose in the world, compute a plan. More...
 
bool makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
 Given a goal pose in the world, compute a plan. More...
 
bool makePlanService (nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
 
 NavfnROS ()
 Default constructor for the NavFnROS object. More...
 
 NavfnROS (std::string name, costmap_2d::Costmap2D *costmap, std::string global_frame)
 Constructor for the NavFnROS object. More...
 
 NavfnROS (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
 Constructor for the NavFnROS object. More...
 
void publishPlan (const std::vector< geometry_msgs::PoseStamped > &path, double r, double g, double b, double a)
 Publish a path for visualization purposes. More...
 
bool validPointPotential (const geometry_msgs::Point &world_point)
 Check for a valid potential value at a given point in the world (Note: You should call computePotential first) More...
 
bool validPointPotential (const geometry_msgs::Point &world_point, double tolerance)
 Check for a valid potential value at a given point in the world (Note: You should call computePotential first) More...
 
 ~NavfnROS ()
 
- Public Member Functions inherited from nav_core::BaseGlobalPlanner
virtual bool makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan, double &cost)
 
virtual ~BaseGlobalPlanner ()
 

Protected Attributes

bool allow_unknown_
 
costmap_2d::Costmap2Dcostmap_
 Store a copy of the current costmap in costmap. Called by makePlan. More...
 
bool initialized_
 
ros::Publisher plan_pub_
 
boost::shared_ptr< NavFnplanner_
 
ros::Publisher potarr_pub_
 
bool visualize_potential_
 

Private Member Functions

void clearRobotCell (const geometry_msgs::PoseStamped &global_pose, unsigned int mx, unsigned int my)
 
void mapToWorld (double mx, double my, double &wx, double &wy)
 
double sq_distance (const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
 

Private Attributes

double default_tolerance_
 
std::string global_frame_
 
ros::ServiceServer make_plan_srv_
 
boost::mutex mutex_
 
double planner_window_x_
 
double planner_window_y_
 

Additional Inherited Members

- Protected Member Functions inherited from nav_core::BaseGlobalPlanner
 BaseGlobalPlanner ()
 

Detailed Description

Provides a ROS wrapper for the navfn planner which runs a fast, interpolated navigation function on a costmap.

Definition at line 91 of file navfn_ros.h.

Constructor & Destructor Documentation

◆ NavfnROS() [1/3]

navfn::NavfnROS::NavfnROS ( )

Default constructor for the NavFnROS object.

Definition at line 83 of file navfn_ros.cpp.

◆ NavfnROS() [2/3]

navfn::NavfnROS::NavfnROS ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
)

Constructor for the NavFnROS object.

Parameters
nameThe name of this planner
costmapA pointer to the ROS wrapper of the costmap to use

Definition at line 86 of file navfn_ros.cpp.

◆ NavfnROS() [3/3]

navfn::NavfnROS::NavfnROS ( std::string  name,
costmap_2d::Costmap2D costmap,
std::string  global_frame 
)

Constructor for the NavFnROS object.

Parameters
nameThe name of this planner
costmapA pointer to the costmap to use
global_frameThe global frame of the costmap

Definition at line 92 of file navfn_ros.cpp.

◆ ~NavfnROS()

navfn::NavfnROS::~NavfnROS ( )
inline

Definition at line 191 of file navfn_ros.h.

Member Function Documentation

◆ clearRobotCell()

void navfn::NavfnROS::clearRobotCell ( const geometry_msgs::PoseStamped &  global_pose,
unsigned int  mx,
unsigned int  my 
)
private

Definition at line 204 of file navfn_ros.cpp.

◆ computePotential()

bool navfn::NavfnROS::computePotential ( const geometry_msgs::Point world_point)

Computes the full navigation function for the map given a point in the world to start from.

Parameters
world_pointThe point to use for seeding the navigation function
Returns
True if the navigation function was computed successfully, false otherwise

Definition at line 176 of file navfn_ros.cpp.

◆ getPlanFromPotential()

bool navfn::NavfnROS::getPlanFromPotential ( const geometry_msgs::PoseStamped &  goal,
std::vector< geometry_msgs::PoseStamped > &  plan 
)

Compute a plan to a goal after the potential for a start point has already been computed (Note: You should call computePotential first)

Parameters
goalThe goal pose to create a plan to
planThe plan... filled by the planner
Returns
True if a valid plan was found, false otherwise

Definition at line 405 of file navfn_ros.cpp.

◆ getPointPotential()

double navfn::NavfnROS::getPointPotential ( const geometry_msgs::Point world_point)

Get the potential, or naviagation cost, at a given point in the world (Note: You should call computePotential first)

Parameters
world_pointThe point to get the potential for
Returns
The navigation function's value at that point in the world

Definition at line 162 of file navfn_ros.cpp.

◆ initialize() [1/2]

void navfn::NavfnROS::initialize ( std::string  name,
costmap_2d::Costmap2D costmap,
std::string  global_frame 
)

Initialization function for the NavFnROS object.

Parameters
nameThe name of this planner
costmapA pointer to the costmap to use for planning
global_frameThe global frame of the costmap

Definition at line 98 of file navfn_ros.cpp.

◆ initialize() [2/2]

void navfn::NavfnROS::initialize ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
)
virtual

Initialization function for the NavFnROS object.

Parameters
nameThe name of this planner
costmapA pointer to the ROS wrapper of the costmap to use for planning

Implements nav_core::BaseGlobalPlanner.

Definition at line 127 of file navfn_ros.cpp.

◆ makePlan() [1/2]

bool navfn::NavfnROS::makePlan ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
double  tolerance,
std::vector< geometry_msgs::PoseStamped > &  plan 
)

Given a goal pose in the world, compute a plan.

Parameters
startThe start pose
goalThe goal pose
toleranceThe tolerance on the goal point for the planner
planThe plan... filled by the planner
Returns
True if a valid plan was found, false otherwise

Definition at line 233 of file navfn_ros.cpp.

◆ makePlan() [2/2]

bool navfn::NavfnROS::makePlan ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
std::vector< geometry_msgs::PoseStamped > &  plan 
)
virtual

Given a goal pose in the world, compute a plan.

Parameters
startThe start pose
goalThe goal pose
planThe plan... filled by the planner
Returns
True if a valid plan was found, false otherwise

Implements nav_core::BaseGlobalPlanner.

Definition at line 228 of file navfn_ros.cpp.

◆ makePlanService()

bool navfn::NavfnROS::makePlanService ( nav_msgs::GetPlan::Request &  req,
nav_msgs::GetPlan::Response &  resp 
)

Definition at line 214 of file navfn_ros.cpp.

◆ mapToWorld()

void navfn::NavfnROS::mapToWorld ( double  mx,
double  my,
double &  wx,
double &  wy 
)
private

Definition at line 223 of file navfn_ros.cpp.

◆ publishPlan()

void navfn::NavfnROS::publishPlan ( const std::vector< geometry_msgs::PoseStamped > &  path,
double  r,
double  g,
double  b,
double  a 
)

Publish a path for visualization purposes.

Definition at line 378 of file navfn_ros.cpp.

◆ sq_distance()

double navfn::NavfnROS::sq_distance ( const geometry_msgs::PoseStamped &  p1,
const geometry_msgs::PoseStamped &  p2 
)
inlineprivate

Definition at line 208 of file navfn_ros.h.

◆ validPointPotential() [1/2]

bool navfn::NavfnROS::validPointPotential ( const geometry_msgs::Point world_point)

Check for a valid potential value at a given point in the world (Note: You should call computePotential first)

Parameters
world_pointThe point to get the potential for
Returns
True if the navigation function is valid at that point in the world, false otherwise

Definition at line 131 of file navfn_ros.cpp.

◆ validPointPotential() [2/2]

bool navfn::NavfnROS::validPointPotential ( const geometry_msgs::Point world_point,
double  tolerance 
)

Check for a valid potential value at a given point in the world (Note: You should call computePotential first)

Parameters
world_pointThe point to get the potential for
toleranceThe tolerance on searching around the world_point specified
Returns
True if the navigation function is valid at that point in the world, false otherwise

Definition at line 135 of file navfn_ros.cpp.

Member Data Documentation

◆ allow_unknown_

bool navfn::NavfnROS::allow_unknown_
protected

Definition at line 204 of file navfn_ros.h.

◆ costmap_

costmap_2d::Costmap2D* navfn::NavfnROS::costmap_
protected

Store a copy of the current costmap in costmap. Called by makePlan.

Definition at line 200 of file navfn_ros.h.

◆ default_tolerance_

double navfn::NavfnROS::default_tolerance_
private

Definition at line 216 of file navfn_ros.h.

◆ global_frame_

std::string navfn::NavfnROS::global_frame_
private

Definition at line 219 of file navfn_ros.h.

◆ initialized_

bool navfn::NavfnROS::initialized_
protected

Definition at line 204 of file navfn_ros.h.

◆ make_plan_srv_

ros::ServiceServer navfn::NavfnROS::make_plan_srv_
private

Definition at line 218 of file navfn_ros.h.

◆ mutex_

boost::mutex navfn::NavfnROS::mutex_
private

Definition at line 217 of file navfn_ros.h.

◆ plan_pub_

ros::Publisher navfn::NavfnROS::plan_pub_
protected

Definition at line 202 of file navfn_ros.h.

◆ planner_

boost::shared_ptr<NavFn> navfn::NavfnROS::planner_
protected

Definition at line 201 of file navfn_ros.h.

◆ planner_window_x_

double navfn::NavfnROS::planner_window_x_
private

Definition at line 216 of file navfn_ros.h.

◆ planner_window_y_

double navfn::NavfnROS::planner_window_y_
private

Definition at line 216 of file navfn_ros.h.

◆ potarr_pub_

ros::Publisher navfn::NavfnROS::potarr_pub_
protected

Definition at line 203 of file navfn_ros.h.

◆ visualize_potential_

bool navfn::NavfnROS::visualize_potential_
protected

Definition at line 204 of file navfn_ros.h.


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


navfn
Author(s): Kurt Konolige, Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:37