Skip to content

Commit b204952

Browse files
committed
added default tolerance and fixed behavior when a goal is obstructed
1 parent b496f68 commit b204952

File tree

2 files changed

+88
-17
lines changed

2 files changed

+88
-17
lines changed

global_planner/include/global_planner/planner_core.h

+1
Original file line numberDiff line numberDiff line change
@@ -178,6 +178,7 @@ class GlobalPlanner : public nav_core::BaseGlobalPlanner {
178178
bool worldToMap(double wx, double wy, double& mx, double& my);
179179
void clearRobotCell(const geometry_msgs::PoseStamped& global_pose, unsigned int mx, unsigned int my);
180180
void publishPotential(float* potential);
181+
std::vector<std::pair<double, double>> findToleratedPoints(double world_x, double world_y, double tolerance, int resol);
181182

182183
double planner_window_x_, planner_window_y_, default_tolerance_;
183184
boost::mutex mutex_;

global_planner/src/planner_core.cpp

+87-17
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,14 @@
4646
#include <global_planner/gradient_path.h>
4747
#include <global_planner/quadratic_calculator.h>
4848

49+
#include <geometry_msgs/Twist.h>
50+
51+
#include <math.h>
52+
#include <algorithm>
53+
#include <cmath>
54+
#define PI 3.14159265
55+
56+
4957
//register this planner as a BaseGlobalPlanner plugin
5058
PLUGINLIB_EXPORT_CLASS(global_planner::GlobalPlanner, nav_core::BaseGlobalPlanner)
5159

@@ -208,6 +216,23 @@ bool GlobalPlanner::worldToMap(double wx, double wy, double& mx, double& my) {
208216
return false;
209217
}
210218

219+
std::vector<std::pair<double, double>> GlobalPlanner::findToleratedPoints(double world_x, double world_y, double tolerance, int resol) {
220+
double alpha = 2*PI/resol;
221+
std::vector<std::pair<double, double>> result;
222+
223+
double map_x, map_y;
224+
worldToMap(world_x, world_y, map_x, map_y);
225+
result.push_back({map_x, map_y});
226+
for (size_t i = 0; i < resol; ++i) {
227+
double x = world_x + tolerance*cos(alpha*i);
228+
double y = world_y + tolerance*sin(alpha*i);
229+
230+
worldToMap(x,y, x,y);
231+
result.push_back({x,y});
232+
}
233+
return result;
234+
}
235+
211236
bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,
212237
std::vector<geometry_msgs::PoseStamped>& plan) {
213238
return makePlan(start, goal, default_tolerance_, plan);
@@ -222,6 +247,7 @@ bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geom
222247
return false;
223248
}
224249

250+
225251
//clear the plan, just in case
226252
plan.clear();
227253

@@ -287,27 +313,70 @@ bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geom
287313

288314
if(outline_map_)
289315
outlineMap(costmap_->getCharMap(), nx, ny, costmap_2d::LETHAL_OBSTACLE);
316+
317+
auto goals = findToleratedPoints(wx, wy, tolerance, 8);
318+
290319

291-
bool found_legal = planner_->calculatePotentials(costmap_->getCharMap(), start_x, start_y, goal_x, goal_y,
320+
321+
std::sort(std::next(goals.begin()), goals.end(), [&start_x, &start_y](const std::pair<double, double>& lhs, const std::pair<double, double>& rhs){
322+
return pow( pow(start_x-lhs.first, 2.0) + pow(start_y-lhs.second, 2.0), 0.5) < pow( pow(start_x-rhs.first, 2.0) + pow(start_y-rhs.second, 2.0), 0.5);
323+
});
324+
325+
for (auto item : goals) {
326+
327+
bool found_legal = planner_->calculatePotentials(costmap_->getCharMap(), start_x, start_y, item.first, item.second,
292328
nx * ny * 2, potential_array_);
329+
330+
331+
//change original goal to a tolerated one
332+
double goal_x_world, goal_y_world;
333+
mapToWorld(item.first, item.second, goal_x_world, goal_y_world);
334+
costmap_->worldToMap(goal_x_world, goal_y_world, goal_x_i, goal_y_i);
335+
336+
geometry_msgs::PoseStamped goal_tol;
337+
goal_tol.header = goal.header;
338+
goal_tol.pose.position.x = goal_x_world;
339+
goal_tol.pose.position.y = goal_y_world;
340+
goal_tol.pose.position.z = goal.pose.position.z;
341+
goal_tol.pose.orientation = goal.pose.orientation;
293342

294-
if(!old_navfn_behavior_)
295-
planner_->clearEndpoint(costmap_->getCharMap(), potential_array_, goal_x_i, goal_y_i, 2);
296-
if(publish_potential_)
297-
publishPotential(potential_array_);
298-
299-
if (found_legal) {
300-
//extract the plan
301-
if (getPlanFromPotential(start_x, start_y, goal_x, goal_y, goal, plan)) {
302-
//make sure the goal we push on has the same timestamp as the rest of the plan
303-
geometry_msgs::PoseStamped goal_copy = goal;
304-
goal_copy.header.stamp = ros::Time::now();
305-
plan.push_back(goal_copy);
306-
} else {
307-
ROS_ERROR("Failed to get a plan from potential when a legal potential was found. This shouldn't happen.");
343+
if(!old_navfn_behavior_)
344+
planner_->clearEndpoint(costmap_->getCharMap(), potential_array_, goal_x_i, goal_y_i, 2);
345+
if(publish_potential_)
346+
publishPotential(potential_array_);
347+
348+
349+
350+
if (found_legal) {
351+
//extract the plan
352+
if (getPlanFromPotential(start_x, start_y, item.first, item.second, goal_tol, plan)) {
353+
//make sure the goal we push on has the same timestamp as the rest of the plan
354+
geometry_msgs::PoseStamped goal_copy = goal_tol;
355+
goal_copy.header.stamp = ros::Time::now();
356+
plan.push_back(goal_copy);
357+
break;
358+
} else {
359+
ROS_ERROR("Failed to get a plan from potential when a legal potential was found. This shouldn't happen.");
360+
break;
361+
}
362+
}else{
363+
ROS_ERROR("Failed to get a plan.");
364+
365+
//robot should stop to prevent collision
366+
ros::NodeHandle private_nh("~");
367+
auto pub = private_nh.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
368+
geometry_msgs::Twist vel;
369+
vel.linear.x = 0.0;
370+
vel.linear.y = 0.0;
371+
vel.linear.z = 0.0;
372+
vel.angular.x = 0.0;
373+
vel.angular.y = 0.0;
374+
vel.angular.z = 0.0;
375+
pub.publish(vel);
376+
377+
//changing goal_x, goal_y inside of the tolerance radius
378+
308379
}
309-
}else{
310-
ROS_ERROR("Failed to get a plan.");
311380
}
312381

313382
// add orientations if needed
@@ -316,6 +385,7 @@ bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geom
316385
//publish the plan for visualization purposes
317386
publishPlan(plan);
318387
delete potential_array_;
388+
319389
return !plan.empty();
320390
}
321391

0 commit comments

Comments
 (0)