Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Classes | Public Types | Public Member Functions | Protected Attributes | List of all members
nav2_smac_planner::AnalyticExpansion< NodeT > Class Template Reference
Collaboration diagram for nav2_smac_planner::AnalyticExpansion< NodeT >:
Collaboration graph
[legend]

Classes

struct  AnalyticExpansionNode
 
struct  AnalyticExpansionNodes
 Analytic expansion nodes and associated metadata. More...
 

Public Types

typedef NodeT * NodePtr
 
typedef std::vector< NodePtr > NodeVector
 
typedef NodeT::Coordinates Coordinates
 
typedef std::function< bool(const uint64_t &, NodeT *&)> NodeGetter
 
typedef NodeT::CoordinateVector CoordinateVector
 

Public Member Functions

 AnalyticExpansion (const MotionModel &motion_model, const SearchInfo &search_info, const bool &traverse_unknown, const unsigned int &dim_3_size)
 Constructor for analytic expansion object.
 
void setCollisionChecker (GridCollisionChecker *collision_checker)
 Sets the collision checker and costmap to use in expansion validation. More...
 
NodePtr tryAnalyticExpansion (const NodePtr &current_node, const NodeVector &coarse_check_goals, const NodeVector &fine_check_goals, const CoordinateVector &goals_coords, const NodeGetter &getter, int &iterations, int &closest_distance)
 Attempt an analytic path completion. More...
 
AnalyticExpansionNodes getAnalyticPath (const NodePtr &node, const NodePtr &goal, const NodeGetter &getter, const ompl::base::StateSpacePtr &state_space)
 Perform an analytic path expansion to the goal. More...
 
float refineAnalyticPath (NodePtr &node, const NodePtr &goal_node, const NodeGetter &getter, AnalyticExpansionNodes &analytic_nodes)
 Refined analytic path from the current node to the goal. More...
 
NodePtr setAnalyticPath (const NodePtr &node, const NodePtr &goal, const AnalyticExpansionNodes &expanded_nodes)
 Takes final analytic expansion and appends to current expanded node. More...
 
int countDirectionChanges (const ompl::base::ReedsSheppStateSpace::ReedsSheppPath &path)
 Counts the number of direction changes in a Reeds-Shepp path. More...
 
void cleanNode (const NodePtr &nodes)
 Takes an expanded nodes to clean up, if necessary, of any state information that may be polluting it from a prior search iteration. More...
 
void cleanNode (const NodePtr &node)
 
AnalyticExpansion< Node2D >::AnalyticExpansionNodes getAnalyticPath (const NodePtr &, const NodePtr &, const NodeGetter &, const ompl::base::StateSpacePtr &)
 
float refineAnalyticPath (NodePtr &, const NodePtr &, const NodeGetter &, AnalyticExpansionNodes &)
 
AnalyticExpansion< Node2D >::NodePtr setAnalyticPath (const NodePtr &, const NodePtr &, const AnalyticExpansionNodes &)
 
AnalyticExpansion< Node2D >::NodePtr tryAnalyticExpansion (const NodePtr &, const NodeVector &, const NodeVector &, const CoordinateVector &, const NodeGetter &, int &, int &)
 

Protected Attributes

MotionModel _motion_model
 
SearchInfo _search_info
 
bool _traverse_unknown
 
unsigned int _dim_3_size
 
GridCollisionChecker_collision_checker
 
std::list< std::unique_ptr< NodeT > > _detached_nodes
 

Detailed Description

template<typename NodeT>
class nav2_smac_planner::AnalyticExpansion< NodeT >

Definition at line 38 of file analytic_expansion.hpp.

Member Function Documentation

◆ cleanNode()

template<typename NodeT >
void nav2_smac_planner::AnalyticExpansion< NodeT >::cleanNode ( const NodePtr &  nodes)

Takes an expanded nodes to clean up, if necessary, of any state information that may be polluting it from a prior search iteration.

Parameters
expanded_nodesExpanded node to clean up from search

Definition at line 441 of file analytic_expansion.cpp.

◆ countDirectionChanges()

template<typename NodeT >
int nav2_smac_planner::AnalyticExpansion< NodeT >::countDirectionChanges ( const ompl::base::ReedsSheppStateSpace::ReedsSheppPath &  path)

Counts the number of direction changes in a Reeds-Shepp path.

Parameters
pathThe Reeds-Shepp path to count direction changes in
Returns
The number of direction changes in the path

Definition at line 146 of file analytic_expansion.cpp.

◆ getAnalyticPath()

template<typename NodeT >
AnalyticExpansion< NodeT >::AnalyticExpansionNodes nav2_smac_planner::AnalyticExpansion< NodeT >::getAnalyticPath ( const NodePtr &  node,
const NodePtr &  goal,
const NodeGetter &  getter,
const ompl::base::StateSpacePtr &  state_space 
)

Perform an analytic path expansion to the goal.

Parameters
nodeThe node to start the analytic path from
goalThe goal node to plan to
getterThe function object that gets valid nodes from the graph
state_spaceState space to use for computing analytic expansions
Returns
A set of analytically expanded nodes to the goal from current node, if possible

Definition at line 168 of file analytic_expansion.cpp.

◆ refineAnalyticPath()

template<typename NodeT >
float nav2_smac_planner::AnalyticExpansion< NodeT >::refineAnalyticPath ( NodePtr &  node,
const NodePtr &  goal_node,
const NodeGetter &  getter,
AnalyticExpansionNodes analytic_nodes 
)

Refined analytic path from the current node to the goal.

Parameters
nodeThe node to start the analytic path from. Node head may change as a result of refinement
goal_nodeThe goal node to plan to
getterThe function object that gets valid nodes from the graph
analytic_nodesThe set of analytic nodes to refine
Returns
The score of the refined path

Definition at line 305 of file analytic_expansion.cpp.

◆ setAnalyticPath()

template<typename NodeT >
AnalyticExpansion< NodeT >::NodePtr nav2_smac_planner::AnalyticExpansion< NodeT >::setAnalyticPath ( const NodePtr &  node,
const NodePtr &  goal,
const AnalyticExpansionNodes expanded_nodes 
)

Takes final analytic expansion and appends to current expanded node.

Parameters
nodeThe node to start the analytic path from
goalThe goal node to plan to
expanded_nodesExpanded nodes to append to end of current search path
Returns
Node pointer to goal node if successful, else return nullptr

Definition at line 404 of file analytic_expansion.cpp.

◆ setCollisionChecker()

template<typename NodeT >
void nav2_smac_planner::AnalyticExpansion< NodeT >::setCollisionChecker ( GridCollisionChecker collision_checker)

Sets the collision checker and costmap to use in expansion validation.

Parameters
collision_checkerCollision checker to use

Definition at line 39 of file analytic_expansion.cpp.

◆ tryAnalyticExpansion()

template<typename NodeT >
AnalyticExpansion< NodeT >::NodePtr nav2_smac_planner::AnalyticExpansion< NodeT >::tryAnalyticExpansion ( const NodePtr &  current_node,
const NodeVector &  coarse_check_goals,
const NodeVector &  fine_check_goals,
const CoordinateVector &  goals_coords,
const NodeGetter &  getter,
int &  iterations,
int &  closest_distance 
)

Attempt an analytic path completion.

Parameters
nodeThe node to start the analytic path from
coarse_check_goalsCoarse list of goals nodes to plan to
fine_check_goalsFine list of goals nodes to plan to
goals_coordsvector of goal coordinates to plan to
getterGets a node at a set of coordinates
iterationsIterations to run over
closest_distanceClosest distance to goal
Returns
Node pointer reference to goal node with the best score out of the goals node if successful, else return nullptr

Definition at line 46 of file analytic_expansion.cpp.


The documentation for this class was generated from the following files: