49 cost_interpreter_ = cost_interpreter;
50 private_nh.
param(
"manhattan_heuristic", manhattan_heuristic_,
false);
51 private_nh.
param(
"use_kernel", use_kernel_,
true);
52 private_nh.
param(
"minimum_requeue_change", minimum_requeue_change_, 1.0);
56 const geometry_msgs::Pose2D& start,
const geometry_msgs::Pose2D& goal)
60 potential_grid.
reset();
65 potential_grid.
setValue(goal_i, 0.0);
76 unsigned int width_bound = potential_grid.
getWidth() - 1, height_bound = potential_grid.
getHeight() - 1;
79 while (queue_.size() > 0)
86 if (i == start_i)
return c;
88 double prev_potential = potential_grid(i);
90 if (i.
x < width_bound)
94 if (i.
y < height_bound)
106 float cost = cost_interpreter_->getCost(index.
x, index.
y);
107 if (cost_interpreter_->isLethal(cost))
117 new_potential = prev_potential + cost;
120 if (new_potential >= potential_grid(index) || potential_grid(index) - new_potential < minimum_requeue_change_)
123 potential_grid.
setValue(index, new_potential);
124 queue_.push(
QueueEntry(index, new_potential + getHeuristicValue(index, start_index)));
127 inline unsigned int uintDiff(
const unsigned int a,
const unsigned int b)
129 return (a > b) ? a - b : b - a;
134 unsigned int dx =
uintDiff(start_index.
x, index.
x);
135 unsigned int dy =
uintDiff(start_index.
y, index.
y);
137 if (manhattan_heuristic_)
138 distance =
static_cast<float>(dx + dy);
140 distance = hypot(dx, dy);
141 return distance * cost_interpreter_->getNeutralCost();
Helper Class for sorting indexes by their heuristic.
Potential calculator that explores using a distance heuristic (A*) but not the kernel function...
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
bool add(const actionlib::TwoIntsGoal &req, actionlib::TwoIntsResult &res)
std::priority_queue< QueueEntry, std::vector< QueueEntry >, QueueEntryComparator > AStarQueue
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
unsigned int getHeight() const
void setValue(const unsigned int x, const unsigned int y, const T &value) override
unsigned int uintDiff(const unsigned int a, const unsigned int b)
std::shared_ptr< CostInterpreter > Ptr
unsigned int getWidth() const
NavGridInfo getInfo() const
static float calculateKernel(const PotentialGrid &potential_grid, unsigned char cost, unsigned int x, unsigned int y, CardinalDirection *upstream=nullptr)
std::shared_ptr< Costmap > Ptr
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)