Public Member Functions | Private Member Functions | Private Attributes | List of all members
navfn::NavfnWithCostmap Class Reference
Inheritance diagram for navfn::NavfnWithCostmap:
Inheritance graph
[legend]

Public Member Functions

bool makePlanService (MakeNavPlan::Request &req, MakeNavPlan::Response &resp)
 
 NavfnWithCostmap (string name, Costmap2DROS *cmap)
 
- Public Member Functions inherited from navfn::NavfnROS
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::Costmap2DROS *costmap_ros)
 Initialization function for the NavFnROS object. More...
 
void initialize (std::string name, costmap_2d::Costmap2D *costmap, std::string global_frame)
 Initialization function for the NavFnROS object. 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 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 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::Costmap2DROS *costmap_ros)
 Constructor for the NavFnROS object. More...
 
 NavfnROS (std::string name, costmap_2d::Costmap2D *costmap, std::string global_frame)
 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 ()
 

Private Member Functions

void poseCallback (const rm::PoseStamped::ConstPtr &goal)
 

Private Attributes

Costmap2DROS * cmap_
 
ros::ServiceServer make_plan_service_
 
ros::Subscriber pose_sub_
 

Additional Inherited Members

- Protected Member Functions inherited from nav_core::BaseGlobalPlanner
 BaseGlobalPlanner ()
 
- Protected Attributes inherited from navfn::NavfnROS
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_
 
pcl_ros::Publisher< PotarrPointpotarr_pub_
 
bool visualize_potential_
 

Detailed Description

Definition at line 53 of file navfn_node.cpp.

Constructor & Destructor Documentation

navfn::NavfnWithCostmap::NavfnWithCostmap ( string  name,
Costmap2DROS *  cmap 
)

Definition at line 100 of file navfn_node.cpp.

Member Function Documentation

bool navfn::NavfnWithCostmap::makePlanService ( MakeNavPlan::Request &  req,
MakeNavPlan::Response &  resp 
)

Definition at line 67 of file navfn_node.cpp.

void navfn::NavfnWithCostmap::poseCallback ( const rm::PoseStamped::ConstPtr &  goal)
private

Definition at line 82 of file navfn_node.cpp.

Member Data Documentation

Costmap2DROS* navfn::NavfnWithCostmap::cmap_
private

Definition at line 61 of file navfn_node.cpp.

ros::ServiceServer navfn::NavfnWithCostmap::make_plan_service_
private

Definition at line 62 of file navfn_node.cpp.

ros::Subscriber navfn::NavfnWithCostmap::pose_sub_
private

Definition at line 63 of file navfn_node.cpp.


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


navfn
Author(s): Kurt Konolige, Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:06:04