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> 49 #include <nav_msgs/GetPlan.h> 103 const geometry_msgs::PoseStamped&
goal, std::vector<geometry_msgs::PoseStamped>& plan);
113 bool makePlan(
const geometry_msgs::PoseStamped& start,
114 const geometry_msgs::PoseStamped& goal,
double tolerance, std::vector<geometry_msgs::PoseStamped>& plan);
129 bool getPlanFromPotential(
const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan);
156 void publishPlan(
const std::vector<geometry_msgs::PoseStamped>& path,
double r,
double g,
double b,
double a);
160 bool makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp);
175 inline double sq_distance(
const geometry_msgs::PoseStamped& p1,
const geometry_msgs::PoseStamped& p2){
176 double dx = p1.pose.position.x - p2.pose.position.x;
177 double dy = p1.pose.position.y - p2.pose.position.y;
181 void mapToWorld(
double mx,
double my,
double& wx,
double& wy);
bool visualize_potential_
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_
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...
costmap_2d::Costmap2D * costmap_
Store a copy of the current costmap in costmap. Called by makePlan.
Provides a ROS wrapper for the navfn planner which runs a fast, interpolated navigation function on a...
void clearRobotCell(const tf::Stamped< tf::Pose > &global_pose, unsigned int mx, unsigned int my)
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 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.
ros::ServiceServer make_plan_srv_
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...
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 default_tolerance_
NavfnROS()
Default constructor for the NavFnROS object.
void mapToWorld(double mx, double my, double &wx, double &wy)
pcl_ros::Publisher< PotarrPoint > potarr_pub_
std::string global_frame_
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initialization function for the NavFnROS object.