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)
70 costmap_(NULL), initialized_(false), allow_unknown_(true),
71 p_calc_(NULL), planner_(NULL), path_maker_(NULL), orientation_filter_(NULL),
72 potential_array_(NULL) {
75 GlobalPlanner::GlobalPlanner(std::string name,
costmap_2d::Costmap2D* costmap, std::string frame_id) :
81 GlobalPlanner::~GlobalPlanner() {
96 void GlobalPlanner::initialize(std::string name,
costmap_2d::Costmap2D* costmap, std::string frame_id) {
100 frame_id_ = frame_id;
104 private_nh.param(
"old_navfn_behavior", old_navfn_behavior_,
false);
105 if(!old_navfn_behavior_)
106 convert_offset_ = 0.5;
108 convert_offset_ = 0.0;
111 private_nh.param(
"use_quadratic", use_quadratic,
true);
118 private_nh.param(
"use_dijkstra", use_dijkstra,
true);
122 if(!old_navfn_behavior_)
130 private_nh.param(
"use_grid_path", use_grid_path,
false);
138 plan_pub_ = private_nh.advertise<nav_msgs::Path>(
"plan", 1);
139 potential_pub_ = private_nh.advertise<nav_msgs::OccupancyGrid>(
"potential", 1);
141 private_nh.param(
"allow_unknown", allow_unknown_,
true);
142 planner_->setHasUnknown(allow_unknown_);
143 private_nh.param(
"planner_window_x", planner_window_x_, 0.0);
144 private_nh.param(
"planner_window_y", planner_window_y_, 0.0);
145 private_nh.param(
"default_tolerance", default_tolerance_, 0.0);
146 private_nh.param(
"publish_scale", publish_scale_, 100);
147 private_nh.param(
"outline_map", outline_map_,
true);
149 make_plan_srv_ = private_nh.advertiseService(
"make_plan", &GlobalPlanner::makePlanService,
this);
151 dsrv_ =
new dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>(
ros::NodeHandle(
"~/" + name));
152 dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>::CallbackType cb =
153 [
this](
auto& config,
auto level){ reconfigureCB(config, level); };
154 dsrv_->setCallback(cb);
158 ROS_WARN(
"This planner has already been initialized, you can't call it twice, doing nothing");
162 void GlobalPlanner::reconfigureCB(global_planner::GlobalPlannerConfig& config, uint32_t level) {
163 planner_->setLethalCost(config.lethal_cost);
164 path_maker_->setLethalCost(config.lethal_cost);
165 planner_->setNeutralCost(config.neutral_cost);
166 planner_->setFactor(config.cost_factor);
167 publish_potential_ = config.publish_potential;
168 orientation_filter_->setMode(config.orientation_mode);
169 orientation_filter_->setWindowSize(config.orientation_window_size);
172 void GlobalPlanner::clearRobotCell(
const geometry_msgs::PoseStamped& global_pose,
unsigned int mx,
unsigned int my) {
175 "This planner has not been initialized yet, but it is being used, please call initialize() before use");
183 bool GlobalPlanner::makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp) {
184 makePlan(req.start, req.goal, resp.plan.poses);
187 resp.plan.header.frame_id = frame_id_;
192 void GlobalPlanner::mapToWorld(
double mx,
double my,
double& wx,
double& wy) {
193 wx = costmap_->getOriginX() + (mx+convert_offset_) * costmap_->getResolution();
194 wy = costmap_->getOriginY() + (my+convert_offset_) * costmap_->getResolution();
197 bool GlobalPlanner::worldToMap(
double wx,
double wy,
double& mx,
double& my) {
198 double origin_x = costmap_->getOriginX(), origin_y = costmap_->getOriginY();
199 double resolution = costmap_->getResolution();
201 if (wx < origin_x || wy < origin_y)
204 mx = (wx - origin_x) / resolution - convert_offset_;
205 my = (wy - origin_y) / resolution - convert_offset_;
207 if (mx < costmap_->getSizeInCellsX() && my < costmap_->getSizeInCellsY())
213 bool GlobalPlanner::makePlan(
const geometry_msgs::PoseStamped& start,
const geometry_msgs::PoseStamped& goal,
214 std::vector<geometry_msgs::PoseStamped>& plan) {
215 return makePlan(
start,
goal, default_tolerance_, plan);
218 bool GlobalPlanner::makePlan(
const geometry_msgs::PoseStamped& start,
const geometry_msgs::PoseStamped& goal,
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");
231 std::string global_frame = frame_id_;
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;
252 if (!costmap_->worldToMap(wx, wy, start_x_i, start_y_i)) {
254 "The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?");
257 if(old_navfn_behavior_){
261 worldToMap(wx, wy, start_x, start_y);
264 wx =
goal.pose.position.x;
265 wy =
goal.pose.position.y;
267 if (!costmap_->worldToMap(wx, wy, goal_x_i, goal_y_i)) {
269 "The goal sent to the global planner is off the global costmap. Planning will always fail to this goal.");
272 if(old_navfn_behavior_){
276 worldToMap(wx, wy, goal_x, goal_y);
280 clearRobotCell(start, start_x_i, start_y_i);
282 int nx = costmap_->getSizeInCellsX(), ny = costmap_->getSizeInCellsY();
285 p_calc_->setSize(nx, ny);
286 planner_->setSize(nx, ny);
287 path_maker_->setSize(nx, ny);
288 potential_array_ =
new float[nx * ny];
293 bool found_legal = planner_->calculatePotentials(costmap_->getCharMap(), start_x, start_y, goal_x, goal_y,
294 nx * ny * 2, potential_array_);
296 if(!old_navfn_behavior_)
297 planner_->clearEndpoint(costmap_->getCharMap(), potential_array_, goal_x_i, goal_y_i, 2);
298 if(publish_potential_)
299 publishPotential(potential_array_);
303 if (getPlanFromPotential(start_x, start_y, goal_x, goal_y, goal, plan)) {
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.");
316 orientation_filter_->processPath(start, plan);
320 delete[] potential_array_;
321 return !plan.empty();
324 void GlobalPlanner::publishPlan(
const std::vector<geometry_msgs::PoseStamped>& path) {
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());
335 gui_path.header.frame_id = frame_id_;
339 for (
unsigned int i = 0; i < path.size(); i++) {
340 gui_path.poses[i] = path[i];
343 plan_pub_.publish(gui_path);
346 bool GlobalPlanner::getPlanFromPotential(
double start_x,
double start_y,
double goal_x,
double goal_y,
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");
355 std::string global_frame = frame_id_;
360 std::vector<std::pair<float, float> > path;
362 if (!path_maker_->getPath(potential_array_, start_x, start_y, goal_x, goal_y, 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);
386 if(old_navfn_behavior_){
387 plan.push_back(
goal);
389 return !plan.empty();
392 void GlobalPlanner::publishPotential(
float* potential)
394 int nx = costmap_->getSizeInCellsX(), ny = costmap_->getSizeInCellsY();
395 double resolution = costmap_->getResolution();
396 nav_msgs::OccupancyGrid grid;
398 grid.header.frame_id = frame_id_;
400 grid.info.resolution = resolution;
402 grid.info.width = nx;
403 grid.info.height = ny;
406 costmap_->mapToWorld(0, 0, wx, wy);
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++) {
416 float potential = potential_array_[i];
418 if (potential > max) {
424 for (
unsigned int i = 0; i < grid.data.size(); i++) {
425 if (potential_array_[i] >=
POT_HIGH) {
428 if (fabs(max) < DBL_EPSILON) {
431 grid.data[i] = potential_array_[i] * publish_scale_ / max;
435 potential_pub_.publish(grid);