Class Node2D

Nested Relationships

Nested Types

Class Documentation

class Node2D

Node2D implementation for graph.

Public Types

typedef Node2D *NodePtr
typedef std::unique_ptr<std::vector<Node2D>> Graph
typedef std::vector<NodePtr> NodeVector
typedef std::vector<Coordinates> CoordinateVector

Public Functions

explicit Node2D(const unsigned int index)

A constructor for nav2_smac_planner::Node2D.

Parameters:

index – The index of this node for self-reference

~Node2D()

A destructor for nav2_smac_planner::Node2D.

inline bool operator==(const Node2D &rhs)

operator== for comparisons

Parameters:

Node2D – right hand side node reference

Returns:

If cell indicies are equal

void reset()

Reset method for new search.

inline float &getAccumulatedCost()

Gets the accumulated cost at this node.

Returns:

accumulated cost

inline void setAccumulatedCost(const float &cost_in)

Sets the accumulated cost at this node.

Parameters:

reference – to accumulated cost

inline float &getCost()

Gets the costmap cost at this node.

Returns:

costmap cost

inline void setCost(const float &cost)

Gets the costmap cost at this node.

Returns:

costmap cost

inline bool &wasVisited()

Gets if cell has been visited in search.

Parameters:

If – cell was visited

inline void visited()

Sets if cell has been visited in search.

inline bool &isQueued()

Gets if cell is currently queued in search.

Parameters:

If – cell was queued

inline void queued()

Sets if cell is currently queued in search.

inline unsigned int &getIndex()

Gets cell index.

Returns:

Reference to cell index

bool isNodeValid(const bool &traverse_unknown, GridCollisionChecker *collision_checker)

Check if this node is valid.

Parameters:
  • traverse_unknown – If we can explore unknown nodes on the graph

  • collision_checker – Pointer to collision checker object

Returns:

whether this node is valid and collision free

float getTraversalCost(const NodePtr &child)

get traversal cost from this node to child node

Parameters:

child – Node pointer to this node’s child

Returns:

traversal cost

void getNeighbors(std::function<bool(const unsigned int&, nav2_smac_planner::Node2D*&)> &validity_checker, GridCollisionChecker *collision_checker, const bool &traverse_unknown, NodeVector &neighbors)

Retrieve all valid neighbors of a node.

Parameters:
  • validity_checker – Functor for state validity checking

  • collision_checker – Collision checker to use

  • traverse_unknown – If unknown costs are valid to traverse

  • neighbors – Vector of neighbors to be filled

bool backtracePath(CoordinateVector &path)

Set the starting pose for planning, as a node index.

Parameters:

path – Reference to a vector of indicies of generated path

Returns:

whether the path was able to be backtraced

Public Members

Node2D *parent

Public Static Functions

static inline unsigned int getIndex(const unsigned int &x, const unsigned int &y, const unsigned int &width)

Get index.

Parameters:
  • x – x coordinate of point to get index of

  • y – y coordinate of point to get index of

  • width – width of costmap

Returns:

index

static inline Coordinates getCoords(const unsigned int &index, const unsigned int &width, const unsigned int &angles)

Get index.

Parameters:
  • Index – Index of point

  • width – width of costmap

  • angles – angle bins to use (must be 1 or throws exception)

Returns:

coordinates of point

static inline Coordinates getCoords(const unsigned int &index)

Get index.

Parameters:

Index – Index of point

Returns:

coordinates of point

static float getHeuristicCost(const Coordinates &node_coords, const Coordinates &goal_coordinates, const nav2_costmap_2d::Costmap2D *costmap)

Get cost of heuristic of node.

Parameters:
  • node – Node index current

  • node – Node index of new

  • costmap – Costmap ptr to use

Returns:

Heuristic cost between the nodes

static void initMotionModel(const MotionModel &motion_model, unsigned int &size_x, unsigned int &size_y, unsigned int &num_angle_quantization, SearchInfo &search_info)

Initialize the neighborhood to be used in A* We support 4-connect (VON_NEUMANN) and 8-connect (MOORE)

Parameters:
  • neighborhood – The desired neighborhood type

  • x_size_uint – The total x size to find neighbors

  • y_size – The total y size to find neighbors

  • num_angle_quantization – Number of quantizations, must be 0

  • search_info – Search parameters, unused by 2D node

Public Static Attributes

static float cost_travel_multiplier
static std::vector<int> _neighbors_grid_offsets
class Coordinates

Node2D implementation of coordinate structure.

Public Functions

inline Coordinates()
inline Coordinates(const float &x_in, const float &y_in)

Public Members

float x
float y