Skip to content

Commit 5ff8cc7

Browse files
Remove redundant collision checks in the Smac Planners to optimize performance (#4857)
* initial prototype to resolve smac planner issue Signed-off-by: Steve Macenski <[email protected]> * fix test Signed-off-by: Steve Macenski <[email protected]> * initial prototype for coarse to fine checking for smac: incomplete Signed-off-by: Steve Macenski <[email protected]> * completed initial prototype; for testing and benchmarking now Signed-off-by: Steve Macenski <[email protected]> * fix typo Signed-off-by: Steve Macenski <[email protected]> * adding bounds checking for coarse Signed-off-by: Steve Macenski <[email protected]> * fix test Signed-off-by: Steve Macenski <[email protected]> * remove coarse to fine checks Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Steve Macenski <[email protected]>
1 parent 694a222 commit 5ff8cc7

File tree

10 files changed

+51
-18
lines changed

10 files changed

+51
-18
lines changed

nav2_smac_planner/include/nav2_smac_planner/a_star.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -240,6 +240,8 @@ class AStarAlgorithm
240240
*/
241241
inline void clearGraph();
242242

243+
inline bool onVisitationCheckNode(const NodePtr & node);
244+
243245
/**
244246
* @brief Populate a debug log of expansions for Hybrid-A* for visualization
245247
* @param node Node expanded

nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,6 @@ class GridCollisionChecker
113113
*/
114114
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> getCostmapROS() {return costmap_ros_;}
115115

116-
private:
117116
/**
118117
* @brief Check if value outside the range
119118
* @param min Minimum value of the range
@@ -128,7 +127,7 @@ class GridCollisionChecker
128127
std::vector<nav2_costmap_2d::Footprint> oriented_footprints_;
129128
nav2_costmap_2d::Footprint unoriented_footprint_;
130129
float center_cost_;
131-
bool footprint_is_radius_;
130+
bool footprint_is_radius_{false};
132131
std::vector<float> angles_;
133132
float possible_collision_cost_{-1};
134133
rclcpp::Logger logger_{rclcpp::get_logger("SmacPlannerCollisionChecker")};

nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -273,6 +273,7 @@ class Node2D
273273
uint64_t _index;
274274
bool _was_visited;
275275
bool _is_queued;
276+
bool _in_collision{false};
276277
};
277278

278279
} // namespace nav2_smac_planner

nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -301,9 +301,12 @@ class NodeHybrid
301301
/**
302302
* @brief Check if this node is valid
303303
* @param traverse_unknown If we can explore unknown nodes on the graph
304+
* @param collision_checker: Collision checker object
304305
* @return whether this node is valid and collision free
305306
*/
306-
bool isNodeValid(const bool & traverse_unknown, GridCollisionChecker * collision_checker);
307+
bool isNodeValid(
308+
const bool & traverse_unknown,
309+
GridCollisionChecker * collision_checker);
307310

308311
/**
309312
* @brief Get traversal cost of parent node to child node
@@ -488,6 +491,7 @@ class NodeHybrid
488491
bool _was_visited;
489492
unsigned int _motion_primitive_index;
490493
TurnDirection _turn_dir;
494+
bool _is_node_valid{false};
491495
};
492496

493497
} // namespace nav2_smac_planner

nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -427,6 +427,7 @@ class NodeLattice
427427
bool _was_visited;
428428
MotionPrimitive * _motion_primitive;
429429
bool _backwards;
430+
bool _is_node_valid{false};
430431
};
431432

432433
} // namespace nav2_smac_planner

nav2_smac_planner/src/a_star.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -326,7 +326,8 @@ bool AStarAlgorithm<NodeT>::createPath(
326326

327327
// We allow for nodes to be queued multiple times in case
328328
// shorter paths result in it, but we can visit only once
329-
if (current_node->wasVisited()) {
329+
// Also a chance to perform last-checks necessary.
330+
if (onVisitationCheckNode(current_node)) {
330331
continue;
331332
}
332333

@@ -435,6 +436,12 @@ float AStarAlgorithm<NodeT>::getHeuristicCost(const NodePtr & node)
435436
return heuristic;
436437
}
437438

439+
template<typename NodeT>
440+
bool AStarAlgorithm<NodeT>::onVisitationCheckNode(const NodePtr & current_node)
441+
{
442+
return current_node->wasVisited();
443+
}
444+
438445
template<typename NodeT>
439446
void AStarAlgorithm<NodeT>::clearQueue()
440447
{

nav2_smac_planner/src/node_2d.cpp

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,8 @@ Node2D::Node2D(const uint64_t index)
3131
_accumulated_cost(std::numeric_limits<float>::max()),
3232
_index(index),
3333
_was_visited(false),
34-
_is_queued(false)
34+
_is_queued(false),
35+
_in_collision(false)
3536
{
3637
}
3738

@@ -47,18 +48,21 @@ void Node2D::reset()
4748
_accumulated_cost = std::numeric_limits<float>::max();
4849
_was_visited = false;
4950
_is_queued = false;
51+
_in_collision = false;
5052
}
5153

5254
bool Node2D::isNodeValid(
5355
const bool & traverse_unknown,
5456
GridCollisionChecker * collision_checker)
5557
{
56-
if (collision_checker->inCollision(this->getIndex(), traverse_unknown)) {
57-
return false;
58+
// Already found, we can return the result
59+
if (!std::isnan(_cell_cost)) {
60+
return !_in_collision;
5861
}
5962

63+
_in_collision = collision_checker->inCollision(this->getIndex(), traverse_unknown);
6064
_cell_cost = collision_checker->getCost();
61-
return true;
65+
return !_in_collision;
6266
}
6367

6468
float Node2D::getTraversalCost(const NodePtr & child)

nav2_smac_planner/src/node_hybrid.cpp

Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -350,7 +350,8 @@ NodeHybrid::NodeHybrid(const uint64_t index)
350350
_accumulated_cost(std::numeric_limits<float>::max()),
351351
_index(index),
352352
_was_visited(false),
353-
_motion_primitive_index(std::numeric_limits<unsigned int>::max())
353+
_motion_primitive_index(std::numeric_limits<unsigned int>::max()),
354+
_is_node_valid(false)
354355
{
355356
}
356357

@@ -369,20 +370,22 @@ void NodeHybrid::reset()
369370
pose.x = 0.0f;
370371
pose.y = 0.0f;
371372
pose.theta = 0.0f;
373+
_is_node_valid = false;
372374
}
373375

374376
bool NodeHybrid::isNodeValid(
375377
const bool & traverse_unknown,
376378
GridCollisionChecker * collision_checker)
377379
{
378-
if (collision_checker->inCollision(
379-
this->pose.x, this->pose.y, this->pose.theta /*bin number*/, traverse_unknown))
380-
{
381-
return false;
380+
// Already found, we can return the result
381+
if (!std::isnan(_cell_cost)) {
382+
return _is_node_valid;
382383
}
383384

385+
_is_node_valid = !collision_checker->inCollision(
386+
this->pose.x, this->pose.y, this->pose.theta /*bin number*/, traverse_unknown);
384387
_cell_cost = collision_checker->getCost();
385-
return true;
388+
return _is_node_valid;
386389
}
387390

388391
float NodeHybrid::getTraversalCost(const NodePtr & child)

nav2_smac_planner/src/node_lattice.cpp

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -194,7 +194,8 @@ NodeLattice::NodeLattice(const uint64_t index)
194194
_index(index),
195195
_was_visited(false),
196196
_motion_primitive(nullptr),
197-
_backwards(false)
197+
_backwards(false),
198+
_is_node_valid(false)
198199
{
199200
}
200201

@@ -214,6 +215,7 @@ void NodeLattice::reset()
214215
pose.theta = 0.0f;
215216
_motion_primitive = nullptr;
216217
_backwards = false;
218+
_is_node_valid = false;
217219
}
218220

219221
bool NodeLattice::isNodeValid(
@@ -222,13 +224,20 @@ bool NodeLattice::isNodeValid(
222224
MotionPrimitive * motion_primitive,
223225
bool is_backwards)
224226
{
227+
// Already found, we can return the result
228+
if (!std::isnan(_cell_cost)) {
229+
return _is_node_valid;
230+
}
231+
225232
// Check primitive end pose
226233
// Convert grid quantization of primitives to radians, then collision checker quantization
227234
static const double bin_size = 2.0 * M_PI / collision_checker->getPrecomputedAngles().size();
228235
const double & angle = motion_table.getAngleFromBin(this->pose.theta) / bin_size;
229236
if (collision_checker->inCollision(
230237
this->pose.x, this->pose.y, angle /*bin in collision checker*/, traverse_unknown))
231238
{
239+
_is_node_valid = false;
240+
_cell_cost = collision_checker->getCost();
232241
return false;
233242
}
234243

@@ -270,6 +279,8 @@ bool NodeLattice::isNodeValid(
270279
prim_pose._theta / bin_size /*bin in collision checker*/,
271280
traverse_unknown))
272281
{
282+
_is_node_valid = false;
283+
_cell_cost = std::max(max_cell_cost, collision_checker->getCost());
273284
return false;
274285
}
275286
max_cell_cost = std::max(max_cell_cost, collision_checker->getCost());
@@ -278,7 +289,8 @@ bool NodeLattice::isNodeValid(
278289
}
279290

280291
_cell_cost = max_cell_cost;
281-
return true;
292+
_is_node_valid = true;
293+
return _is_node_valid;
282294
}
283295

284296
float NodeLattice::getTraversalCost(const NodePtr & child)

nav2_smac_planner/test/test_a_star.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -201,8 +201,8 @@ TEST(AStarTest, test_a_star_se2)
201201
EXPECT_TRUE(a_star.createPath(path, num_it, tolerance, dummy_cancel_checker, expansions.get()));
202202

203203
// check path is the right size and collision free
204-
EXPECT_EQ(num_it, 3146);
205-
EXPECT_EQ(path.size(), 63u);
204+
EXPECT_GT(num_it, 2000);
205+
EXPECT_NEAR(path.size(), 63u, 2u);
206206
for (unsigned int i = 0; i != path.size(); i++) {
207207
EXPECT_EQ(costmapA->getCost(path[i].x, path[i].y), 0);
208208
}

0 commit comments

Comments
 (0)