55 void GlobalPlanner::outlineMap(
unsigned char* costarr,
int nx,
int ny,
unsigned char value) {
56 unsigned char* pc = costarr;
57 for (
int i = 0; i < nx; i++)
59 pc = costarr + (ny - 1) * nx;
60 for (
int i = 0; i < nx; i++)
63 for (
int i = 0; i < ny; i++, pc += nx)
65 pc = costarr + nx - 1;
66 for (
int i = 0; i < ny; i++, pc += nx)
70 GlobalPlanner::GlobalPlanner() :
71 costmap_(NULL), initialized_(false), allow_unknown_(true) {
110 private_nh.
param(
"use_quadratic", use_quadratic,
true);
117 private_nh.
param(
"use_dijkstra", use_dijkstra,
true);
129 private_nh.
param(
"use_grid_path", use_grid_path,
false);
147 double costmap_pub_freq;
148 private_nh.
param(
"planner_costmap_publish_frequency", costmap_pub_freq, 0.0);
156 dsrv_ =
new dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>(
ros::NodeHandle(
"~/" + name));
157 dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>::CallbackType cb = boost::bind(
159 dsrv_->setCallback(cb);
163 ROS_WARN(
"This planner has already been initialized, you can't call it twice, doing nothing");
180 "This planner has not been initialized yet, but it is being used, please call initialize() before use");
189 makePlan(req.start, req.goal, resp.plan.poses);
206 if (wx < origin_x || wy < origin_y)
219 std::vector<geometry_msgs::PoseStamped>& plan) {
224 double tolerance, std::vector<geometry_msgs::PoseStamped>& plan) {
225 boost::mutex::scoped_lock lock(
mutex_);
228 "This planner has not been initialized yet, but it is being used, please call initialize() before use");
251 double wx = start.pose.position.x;
252 double wy = start.pose.position.y;
254 unsigned int start_x_i, start_y_i, goal_x_i, goal_y_i;
255 double start_x, start_y, goal_x, goal_y;
259 "The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?");
269 wx = goal.pose.position.x;
270 wy = goal.pose.position.y;
274 "The goal sent to the global planner is off the global costmap. Planning will always fail to this goal.");
311 geometry_msgs::PoseStamped goal_copy = goal;
313 plan.push_back(goal_copy);
315 ROS_ERROR(
"Failed to get a plan from potential when a legal potential was found. This shouldn't happen.");
327 return !plan.empty();
333 "This planner has not been initialized yet, but it is being used, please call initialize() before use");
338 nav_msgs::Path gui_path;
339 gui_path.poses.resize(path.size());
345 for (
unsigned int i = 0; i < path.size(); i++) {
346 gui_path.poses[i] = path[i];
353 const geometry_msgs::PoseStamped& goal,
354 std::vector<geometry_msgs::PoseStamped>& plan) {
357 "This planner has not been initialized yet, but it is being used, please call initialize() before use");
366 std::vector<std::pair<float, float> > path;
374 for (
int i = path.size() -1; i>=0; i--) {
375 std::pair<float, float> point = path[i];
377 double world_x, world_y;
378 mapToWorld(point.first, point.second, world_x, world_y);
380 geometry_msgs::PoseStamped pose;
381 pose.header.stamp = plan_time;
382 pose.header.frame_id = global_frame;
383 pose.pose.position.x = world_x;
384 pose.pose.position.y = world_y;
385 pose.pose.position.z = 0.0;
386 pose.pose.orientation.x = 0.0;
387 pose.pose.orientation.y = 0.0;
388 pose.pose.orientation.z = 0.0;
389 pose.pose.orientation.w = 1.0;
390 plan.push_back(pose);
393 plan.push_back(goal);
395 return !plan.empty();
402 nav_msgs::OccupancyGrid grid;
406 grid.info.resolution = resolution;
408 grid.info.width = nx;
409 grid.info.height = ny;
413 grid.info.origin.position.x = wx - resolution / 2;
414 grid.info.origin.position.y = wy - resolution / 2;
415 grid.info.origin.position.z = 0.0;
416 grid.info.origin.orientation.w = 1.0;
418 grid.data.resize(nx * ny);
421 for (
unsigned int i = 0; i < grid.data.size(); i++) {
424 if (potential > max) {
430 for (
unsigned int i = 0; i < grid.data.size(); i++) {
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
void clearRobotCell(const tf::Stamped< tf::Pose > &global_pose, unsigned int mx, unsigned int my)
void publishPotential(float *potential)
~GlobalPlanner()
Default deconstructor for the PlannerCore object.
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.
void mapToWorld(double mx, double my, double &wx, double &wy)
void publish(const boost::shared_ptr< M > &message) const
std::string getPrefixParam(ros::NodeHandle &nh)
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
virtual void processPath(const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &path)
void setLethalCost(unsigned char lethal_cost)
void outlineMap(unsigned char *costarr, int nx, int ny, unsigned char value)
virtual void setSize(int nx, int ny)
Sets or resets the size of the map.
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initialization function for the PlannerCore object.
double default_tolerance_
std::string getGlobalFrameID()
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
double getOriginX() const
costmap_2d::Costmap2D * costmap_
Store a copy of the current costmap in costmap. Called by makePlan.
virtual bool getPath(float *potential, double start_x, double start_y, double end_x, double end_y, std::vector< std::pair< float, float > > &path)=0
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void reconfigureCB(global_planner::GlobalPlannerConfig &config, uint32_t level)
static const unsigned char FREE_SPACE
PotentialCalculator * p_calc_
unsigned char * getCharMap() const
void clearEndpoint(unsigned char *costs, float *potential, int gx, int gy, int s)
std::string resolve(const std::string &prefix, const std::string &frame_name)
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path)
Publish a path for visualization purposes.
bool getPlanFromPotential(double start_x, double start_y, double end_x, double end_y, 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...
#define ROS_WARN_THROTTLE(period,...)
void setPreciseStart(bool precise)
void setLethalCost(unsigned char lethal_cost)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool worldToMap(double wx, double wy, double &mx, double &my)
double getOriginY() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned int getSizeInCellsY() const
GlobalPlanner()
Default constructor for the PlannerCore object.
virtual void setSize(int xs, int ys)
OrientationFilter * orientation_filter_
ros::Publisher potential_pub_
void setHasUnknown(bool unknown)
unsigned int getSizeInCellsX() const
bool makePlanService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
ros::ServiceServer make_plan_srv_
static const unsigned char LETHAL_OBSTACLE
virtual bool calculatePotentials(unsigned char *costs, double start_x, double start_y, double end_x, double end_y, int cycles, float *potential)=0
void setMode(OrientationMode new_mode)
static void poseStampedMsgToTF(const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
void setNeutralCost(unsigned char neutral_cost)
double getResolution() const
void setWindowSize(size_t window_size)
void setFactor(float factor)
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
dynamic_reconfigure::Server< global_planner::GlobalPlannerConfig > * dsrv_
virtual void setSize(int nx, int ny)
Sets or resets the size of the map.