51 : costmap_(NULL), planner_(), initialized_(false), allow_unknown_(true) {}
95 ROS_WARN(
"This planner has already been initialized, you can't call it twice, doing nothing");
108 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
113 geometry_msgs::Point p;
116 p.y = world_point.y - tolerance;
118 while(p.y <= world_point.y + tolerance){
119 p.x = world_point.x - tolerance;
120 while(p.x <= world_point.x + tolerance){
135 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
143 unsigned int index = my *
planner_->nx + mx;
149 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
172 return planner_->calcNavFnDijkstra();
177 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
186 makePlan(req.start, req.goal, resp.plan.poses);
200 const geometry_msgs::PoseStamped&
goal, std::vector<geometry_msgs::PoseStamped>& plan){
205 const geometry_msgs::PoseStamped&
goal,
double tolerance, std::vector<geometry_msgs::PoseStamped>& plan){
206 boost::mutex::scoped_lock lock(
mutex_);
208 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
219 ROS_ERROR(
"The goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.",
225 ROS_ERROR(
"The start pose passed to this planner must be in the %s frame. It is instead in the %s frame.",
230 double wx = start.pose.position.x;
231 double wy = start.pose.position.y;
235 ROS_WARN(
"The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?");
248 snprintf( filename, 1000,
"navfnros-makeplan-costmapB-%04d.pgm", n++ );
249 costmap->saveRawMap( std::string( filename ));
261 snprintf( filename, 1000,
"navfnros-makeplan-costmapC-%04d", n++ );
270 wx = goal.pose.position.x;
271 wy = goal.pose.position.y;
274 if(tolerance <= 0.0){
275 ROS_WARN_THROTTLE(1.0,
"The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal.");
293 geometry_msgs::PoseStamped p, best_pose;
296 bool found_legal =
false;
297 double best_sdist = DBL_MAX;
299 p.pose.position.y = goal.pose.position.y - tolerance;
301 while(p.pose.position.y <= goal.pose.position.y + tolerance){
302 p.pose.position.x = goal.pose.position.x - tolerance;
303 while(p.pose.position.x <= goal.pose.position.x + tolerance){
306 if(potential <
POT_HIGH && sdist < best_sdist){
311 p.pose.position.x += resolution;
313 p.pose.position.y += resolution;
320 geometry_msgs::PoseStamped goal_copy = best_pose;
322 plan.push_back(goal_copy);
325 ROS_ERROR(
"Failed to get a plan from potential when a legal potential was found. This shouldn't happen.");
331 pcl::PointCloud<PotarrPoint> pot_area;
333 pot_area.points.clear();
334 std_msgs::Header header;
351 pot_area.push_back(pt);
360 return !plan.empty();
363 void NavfnROS::publishPlan(
const std::vector<geometry_msgs::PoseStamped>& path,
double r,
double g,
double b,
double a){
365 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
370 nav_msgs::Path gui_path;
371 gui_path.poses.resize(path.size());
375 gui_path.header.frame_id = path[0].header.frame_id;
376 gui_path.header.stamp = path[0].header.stamp;
380 for(
unsigned int i=0; i < path.size(); i++){
381 gui_path.poses[i] = path[i];
389 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
398 ROS_ERROR(
"The goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.",
403 double wx = goal.pose.position.x;
404 double wy = goal.pose.position.y;
409 ROS_WARN_THROTTLE(1.0,
"The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal.");
427 for(
int i = len - 1; i >= 0; --i){
429 double world_x, world_y;
432 geometry_msgs::PoseStamped pose;
433 pose.header.stamp = plan_time;
435 pose.pose.position.x = world_x;
436 pose.pose.position.y = world_y;
437 pose.pose.position.z = 0.0;
438 pose.pose.orientation.x = 0.0;
439 pose.pose.orientation.y = 0.0;
440 pose.pose.orientation.z = 0.0;
441 pose.pose.orientation.w = 1.0;
442 plan.push_back(pose);
447 return !plan.empty();
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
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.
#define ROS_WARN_THROTTLE(rate,...)
boost::shared_ptr< NavFn > planner_
void publish(const boost::shared_ptr< M > &message) const
std::string getPrefixParam(ros::NodeHandle &nh)
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...
std::string getGlobalFrameID()
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
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...
double getOriginX() const
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...
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
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.
TFSIMD_FORCE_INLINE const tfScalar & y() const
static const unsigned char FREE_SPACE
unsigned char * getCharMap() const
std::string resolve(const std::string &prefix, const std::string &frame_name)
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
ros::ServiceServer make_plan_srv_
double sq_distance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
Navigation function class. Holds buffers for costmap, navfn map. Maps are pixel-based. Origin is upper left, x is right, y is down.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
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...
TFSIMD_FORCE_INLINE const tfScalar & x() const
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...
double getOriginY() const
bool makePlanService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned int getSizeInCellsY() const
double default_tolerance_
NavfnROS()
Default constructor for the NavFnROS object.
unsigned int getSizeInCellsX() const
void mapToWorld(double mx, double my, double &wx, double &wy)
static void poseStampedMsgToTF(const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
pcl_ros::Publisher< PotarrPoint > potarr_pub_
std::string global_frame_
double getResolution() const
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initialization function for the NavFnROS object.
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)