Skip to content

Commit

Permalink
commenting out unused validPointPotential (#1854)
Browse files Browse the repository at this point in the history
  • Loading branch information
SteveMacenski authored Jul 7, 2020
1 parent 4755a1e commit 8b8807a
Show file tree
Hide file tree
Showing 2 changed files with 38 additions and 38 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -88,8 +88,8 @@ class NavfnPlanner : public nav2_core::GlobalPlanner
// Check for a valid potential value at a given point in the world
// - must call computePotential first
// - currently unused
bool validPointPotential(const geometry_msgs::msg::Point & world_point);
bool validPointPotential(const geometry_msgs::msg::Point & world_point, double tolerance);
// bool validPointPotential(const geometry_msgs::msg::Point & world_point);
// bool validPointPotential(const geometry_msgs::msg::Point & world_point, double tolerance);

// Compute the squared distance between two points
inline double squared_distance(
Expand Down
72 changes: 36 additions & 36 deletions nav2_navfn_planner/src/navfn_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -357,42 +357,42 @@ NavfnPlanner::getPointPotential(const geometry_msgs::msg::Point & world_point)
return planner_->potarr[index];
}

bool
NavfnPlanner::validPointPotential(const geometry_msgs::msg::Point & world_point)
{
return validPointPotential(world_point, tolerance_);
}

bool
NavfnPlanner::validPointPotential(
const geometry_msgs::msg::Point & world_point, double tolerance)
{
const double resolution = costmap_->getResolution();

geometry_msgs::msg::Point p = world_point;
double potential = getPointPotential(p);
if (potential < POT_HIGH) {
// world_point is reachable by itself
return true;
} else {
// world_point, is not reachable. Trying to find any
// reachable point within its tolerance region
p.y = world_point.y - tolerance;
while (p.y <= world_point.y + tolerance) {
p.x = world_point.x - tolerance;
while (p.x <= world_point.x + tolerance) {
potential = getPointPotential(p);
if (potential < POT_HIGH) {
return true;
}
p.x += resolution;
}
p.y += resolution;
}
}

return false;
}
// bool
// NavfnPlanner::validPointPotential(const geometry_msgs::msg::Point & world_point)
// {
// return validPointPotential(world_point, tolerance_);
// }

// bool
// NavfnPlanner::validPointPotential(
// const geometry_msgs::msg::Point & world_point, double tolerance)
// {
// const double resolution = costmap_->getResolution();

// geometry_msgs::msg::Point p = world_point;
// double potential = getPointPotential(p);
// if (potential < POT_HIGH) {
// // world_point is reachable by itself
// return true;
// } else {
// // world_point, is not reachable. Trying to find any
// // reachable point within its tolerance region
// p.y = world_point.y - tolerance;
// while (p.y <= world_point.y + tolerance) {
// p.x = world_point.x - tolerance;
// while (p.x <= world_point.x + tolerance) {
// potential = getPointPotential(p);
// if (potential < POT_HIGH) {
// return true;
// }
// p.x += resolution;
// }
// p.y += resolution;
// }
// }

// return false;
// }

bool
NavfnPlanner::worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my)
Expand Down

0 comments on commit 8b8807a

Please sign in to comment.