55 unsigned char* pc = costarr;
56 for (
int i = 0; i < nx; i++)
58 pc = costarr + (ny - 1) * nx;
59 for (
int i = 0; i < nx; i++)
62 for (
int i = 0; i < ny; i++, pc += nx)
64 pc = costarr + nx - 1;
65 for (
int i = 0; i < ny; i++, pc += nx)
111 private_nh.
param(
"use_quadratic", use_quadratic,
true);
118 private_nh.
param(
"use_dijkstra", use_dijkstra,
true);
130 private_nh.
param(
"use_grid_path", use_grid_path,
false);
151 dsrv_ =
new dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>(
ros::NodeHandle(
"~/" + name));
152 dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>::CallbackType cb = boost::bind(
154 dsrv_->setCallback(cb);
158 ROS_WARN(
"This planner has already been initialized, you can't call it twice, doing nothing");
175 "This planner has not been initialized yet, but it is being used, please call initialize() before use");
184 makePlan(req.start, req.goal, resp.plan.poses);
201 if (wx < origin_x || wy < origin_y)
214 std::vector<geometry_msgs::PoseStamped>& plan) {
219 double tolerance, std::vector<geometry_msgs::PoseStamped>& plan) {
220 boost::mutex::scoped_lock lock(
mutex_);
223 "This planner has not been initialized yet, but it is being used, please call initialize() before use");
234 if (goal.header.frame_id != global_frame) {
236 "The goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.", global_frame.c_str(), goal.header.frame_id.c_str());
240 if (start.header.frame_id != global_frame) {
242 "The start pose passed to this planner must be in the %s frame. It is instead in the %s frame.", global_frame.c_str(), start.header.frame_id.c_str());
246 double wx = start.pose.position.x;
247 double wy = start.pose.position.y;
249 unsigned int start_x_i, start_y_i, goal_x_i, goal_y_i;
250 double start_x, start_y, goal_x, goal_y;
254 "The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?");
264 wx = goal.pose.position.x;
265 wy = goal.pose.position.y;
269 "The goal sent to the global planner is off the global costmap. Planning will always fail to this goal.");
305 geometry_msgs::PoseStamped goal_copy = goal;
307 plan.push_back(goal_copy);
309 ROS_ERROR(
"Failed to get a plan from potential when a legal potential was found. This shouldn't happen.");
321 return !plan.empty();
327 "This planner has not been initialized yet, but it is being used, please call initialize() before use");
332 nav_msgs::Path gui_path;
333 gui_path.poses.resize(path.size());
339 for (
unsigned int i = 0; i < path.size(); i++) {
340 gui_path.poses[i] = path[i];
347 const geometry_msgs::PoseStamped& goal,
348 std::vector<geometry_msgs::PoseStamped>& plan) {
351 "This planner has not been initialized yet, but it is being used, please call initialize() before use");
360 std::vector<std::pair<float, float> > path;
368 for (
int i = path.size() -1; i>=0; i--) {
369 std::pair<float, float> point = path[i];
371 double world_x, world_y;
372 mapToWorld(point.first, point.second, world_x, world_y);
374 geometry_msgs::PoseStamped pose;
375 pose.header.stamp = plan_time;
376 pose.header.frame_id = global_frame;
377 pose.pose.position.x = world_x;
378 pose.pose.position.y = world_y;
379 pose.pose.position.z = 0.0;
380 pose.pose.orientation.x = 0.0;
381 pose.pose.orientation.y = 0.0;
382 pose.pose.orientation.z = 0.0;
383 pose.pose.orientation.w = 1.0;
384 plan.push_back(pose);
387 plan.push_back(goal);
389 return !plan.empty();
396 nav_msgs::OccupancyGrid grid;
400 grid.info.resolution = resolution;
402 grid.info.width = nx;
403 grid.info.height = ny;
407 grid.info.origin.position.x = wx - resolution / 2;
408 grid.info.origin.position.y = wy - resolution / 2;
409 grid.info.origin.position.z = 0.0;
410 grid.info.origin.orientation.w = 1.0;
412 grid.data.resize(nx * ny);
415 for (
unsigned int i = 0; i < grid.data.size(); i++) {
418 if (potential > max) {
424 for (
unsigned int i = 0; i < grid.data.size(); i++) {
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
void publishPotential(float *potential)
~GlobalPlanner()
Default deconstructor for the PlannerCore object.
unsigned int getSizeInCellsX() const
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)
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)
unsigned int getSizeInCellsY() const
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()
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
double getOriginY() const
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_
void clearEndpoint(unsigned char *costs, float *potential, int gx, int gy, int s)
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path)
Publish a path for visualization purposes.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
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...
unsigned char * getCharMap() const
#define ROS_WARN_THROTTLE(period,...)
void setPreciseStart(bool precise)
void setLethalCost(unsigned char lethal_cost)
bool worldToMap(double wx, double wy, double &mx, double &my)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
GlobalPlanner()
Default constructor for the PlannerCore object.
double getOriginX() const
virtual void setSize(int xs, int ys)
OrientationFilter * orientation_filter_
ros::Publisher potential_pub_
void setHasUnknown(bool unknown)
bool makePlanService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
ros::ServiceServer make_plan_srv_
static const unsigned char LETHAL_OBSTACLE
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
virtual bool calculatePotentials(unsigned char *costs, double start_x, double start_y, double end_x, double end_y, int cycles, float *potential)=0
double getResolution() const
void setMode(OrientationMode new_mode)
void setNeutralCost(unsigned char neutral_cost)
void clearRobotCell(const geometry_msgs::PoseStamped &global_pose, unsigned int mx, unsigned int my)
double max(double a, double b)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
void setWindowSize(size_t window_size)
void setFactor(float factor)
dynamic_reconfigure::Server< global_planner::GlobalPlannerConfig > * dsrv_
virtual void setSize(int nx, int ny)
Sets or resets the size of the map.