23#ifndef _LIBS_NAVGRAPH_NAVGRAPH_PATH_H_
24#define _LIBS_NAVGRAPH_NAVGRAPH_PATH_H_
26#include <navgraph/navgraph_node.h>
77 void assert_initialized()
const;
99 const std::vector<NavGraphNode> &
110 std::vector<NavGraphNode> &
143 std::vector<NavGraphNode> nodes_;
Sub-class representing a navgraph path traversal.
bool last() const
Check if the current node is the last node in the path.
float remaining_cost() const
Get the remaining cost to the goal.
const NavGraphPath & path() const
Get parent path the traversal belongs to.
size_t current_index() const
Get index of current node in path.
void invalidate()
Invalidate this traversal.
const NavGraphNode & current() const
Get current node in path.
bool next()
Move on traversal to next node.
size_t remaining() const
Get the number of remaining nodes in path traversal.
bool running() const
Check if traversal is currently runnung.
void set_current(size_t new_current)
Set the current node.
void reset()
Reset an ongoing traversal.
const NavGraphNode & peek_next() const
Peek on the next node.
Class representing a path for a NavGraph.
std::vector< std::string > get_node_names() const
Get names of nodes in path.
Traversal traversal() const
Get a new path traversal handle.
bool empty() const
Check if path is empty.
bool operator<(const NavGraphPath &p) const
Check if this path is cheaper than the other path.
bool operator==(const NavGraphPath &p) const
Check if two paths are the same.
NavGraphPath()
Default constructor.
size_t size() const
Get size of path.
void clear()
Clear all nodes on this path.
const std::vector< NavGraphNode > & nodes() const
Get nodes along the path.
const NavGraph & graph() const
Get graph this path is based on.
float cost() const
Get cost of path from start to to end.
bool contains(const NavGraphNode &node) const
Check if the path contains a given node.
const NavGraphNode & goal() const
Get goal of path.
std::string get_path_as_string(const char delim=':') const
Get string representation of path.
void add_node(const NavGraphNode &node, float cost_from_end=0)
Add a node to the path.
void set_nodes(const std::vector< NavGraphNode > &nodes, float cost=-1)
Set nodes erasing the current path.
std::vector< NavGraphNode > & nodes_mutable()
Get nodes along the path as mutable vector.
Fawkes library namespace.