Go to the documentation of this file.
   37 #ifndef NAVFN_NAVFN_ROS_H_ 
   38 #define NAVFN_NAVFN_ROS_H_ 
   43 #include <geometry_msgs/PoseStamped.h> 
   44 #include <geometry_msgs/Point.h> 
   45 #include <nav_msgs/Path.h> 
   48 #include <nav_msgs/GetPlan.h> 
  101           const geometry_msgs::PoseStamped& 
goal, std::vector<geometry_msgs::PoseStamped>& plan);
 
  112           const geometry_msgs::PoseStamped& 
goal, 
double tolerance, std::vector<geometry_msgs::PoseStamped>& plan);
 
  154       void publishPlan(
const std::vector<geometry_msgs::PoseStamped>& path, 
double r, 
double g, 
double b, 
double a);
 
  158       bool makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp);
 
  173       inline double sq_distance(
const geometry_msgs::PoseStamped& p1, 
const geometry_msgs::PoseStamped& p2){
 
  174         double dx = p1.pose.position.x - p2.pose.position.x;
 
  175         double dy = p1.pose.position.y - p2.pose.position.y;
 
  179       void mapToWorld(
double mx, 
double my, 
double& wx, 
double& wy);
 
  180       void clearRobotCell(
const geometry_msgs::PoseStamped& global_pose, 
unsigned int mx, 
unsigned int my);
 
  
std::string global_frame_
 
ros::ServiceServer make_plan_srv_
 
NavfnROS()
Default constructor for the NavFnROS object.
 
ros::Publisher potarr_pub_
 
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 s...
 
bool makePlanService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
 
double sq_distance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
 
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 computeP...
 
void clearRobotCell(const geometry_msgs::PoseStamped &global_pose, unsigned int mx, unsigned int my)
 
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, double r, double g, double b, double a)
Publish a path for visualization purposes.
 
boost::shared_ptr< NavFn > planner_
 
double default_tolerance_
 
void mapToWorld(double mx, double my, double &wx, double &wy)
 
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 computePotenti...
 
bool visualize_potential_
 
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initialization function for the NavFnROS object.
 
costmap_2d::Costmap2D * costmap_
Store a copy of the current costmap in costmap. Called by makePlan.
 
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.
 
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.
 
navfn
Author(s): Kurt Konolige, Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:37