Class DerivedResolutionGraph
Defined in File DerivedResolutionGraph.hpp
Class Documentation
-
class DerivedResolutionGraph
Represents a directed graph structure for managing derived predicates and their dependencies in a planning system.
This class is used to model and resolve derived predicates and its dependencies. Check issue #328 for a more detailed explanation. It provides methods for graph construction, traversal (DFS, backtracking), subgraph extraction, and computing the graph’s strongly connected components (SCC). In this graph, nodes in the upper layer (depth 0) represent predicates, functions, or instances. Nodes in the lower layers (depth one or more) represent derived predicates. Nodes in the last layer represent actions. The edges indicate dependencies between the nodes, with arrows pointing from parent to child nodes. More specifically, the graph nodes are instances of the NodeVariant class, which can hold plansys2::Predicate, plansys2::Function, plansys2::Derived, or plansys2::ActionVariant. This definition allows derived predicates to depend on other derived predicates, including recursive self-dependencies, and allows negated derived predicates in their preconditions, provided that such negation does not occur within a recursive cycle.
Key Features:
Construction from various collections of derived predicates.
Methods to add nodes and edges, including from action preconditions.
Multiple traversal strategies (depth-first, backtracking, SCC detection).
Extraction of subgraphs and pruning based on actions.
Query functions for nodes, edges, roots, predicates, functions, and actions.
Export capability to DOT format for visualization.
Equality operator for graph comparison.
Note
NodeVariant, Derived, Predicate, Function, and ActionVariant are types defined in the plansys2 namespace.
Public Types
-
using NodeEdgesMap = std::unordered_map<NodeVariant, std::unordered_set<NodeVariant>>
Public Functions
-
inline DerivedResolutionGraph()
-
DerivedResolutionGraph(const std::vector<plansys2_msgs::msg::Derived> &derived_predicates)
-
void printGraph() const
-
void printGraphLayers() const
-
void addNode(const NodeVariant &node)
-
void addEdge(const NodeVariant &u, const NodeVariant &v)
-
void addEdgeFromPreconditions(const NodeVariant &node, const plansys2_msgs::msg::Tree &tree)
Adds edges to the resolution graph based on the preconditions of a given node.
This method analyzes the preconditions specified in the provided tree and creates corresponding edges in the derived resolution graph, originating from the given node.
- Parameters:
node – The node from which edges will be added, represented as a NodeVariant.
tree – The tree structure containing the preconditions to be analyzed.
-
void depthFirstTraverse(const NodeVariant &start, const std::function<void(const NodeVariant&)> &func, std::unordered_set<NodeVariant> &visited, bool check_dependencies = false) const
Performs a depth first traverse from a given Node and applies func to each node.
This method Performs a depth first traverse from a given Node, applies func to each node, and adds each visited node to the visisted vector to avoid visiting the same node multiple times. When check_dependencies is true, it only expands a node when all its parents were already visited.
- Parameters:
start – The node from which the traverse should start.
func – The function to apply to each node.
visited – unordered_set containing all nodes that were already visisted
check_dependencies – whether to only expand a node if the parents were visisted
-
void depthFirstTraverse(const NodeVariant &start, const std::function<void(const NodeVariant&)> &func, bool check_dependencies = false) const
Performs a depth first traverse from a given Node and applies func to each node.
This method Performs a depth first traverse from a given Node and applies func to each node. When check_dependencies is true, it only expands a node when all its parents were already visited.
- Parameters:
start – The node from which the traverse should start.
func – The function to apply to each node.
check_dependencies – whether to only expand a node if the parents were visisted
-
void depthFirstTraverseFromNodes(const std::function<void(const NodeVariant&)> &func, bool check_dependencies = false, const std::vector<NodeVariant> &start_nodes = {}) const
Performs depth first traverse from a given set of Nodes and applies func to each node.
This method performs a depth first traverse from a given set of Nodes and applies func to each node. When check_dependencies is true, it only expands a node when all its parents were already visited.
- Parameters:
start_nodes – Vector containing the nodes from which the traverse should start.
func – The function to apply to each node.
check_dependencies – whether to only expand a node if the parents were visisted
-
void depthFirstTraverseAll(const std::function<void(const NodeVariant&)> &func, bool check_dependencies = false) const
Performs depth first traverse from all root Nodes and applies func to each node.
This method Performs a depth first traverse from all root Nodes and applies func to each node. When check_dependencies is true, it only expands a node when all its parents were already visited.
- Parameters:
func – The function to apply to each node.
check_dependencies – whether to only expand a node if the parents were visisted
-
std::vector<plansys2::Derived> getDerivedPredicatesDepthFirst(const std::vector<NodeVariant> &start_nodes = {}) const
Retrieves a list of derived predicates using a depth-first traversal.
This method performs a depth-first search starting from the specified nodes (if any), collecting all reachable derived predicates in the order they are discovered.
- Parameters:
start_nodes – Optional vector of starting nodes for the traversal. If empty, the traversal will start from all root nodes in the graph.
- Returns:
std::vector<plansys2::Derived> A vector containing the derived predicates found during traversal.
-
std::deque<plansys2::Derived> getDerivedPredicatesFromActions(const std::vector<plansys2::ActionVariant> &actions) const
Retrieves a list of derived predicates that given actions depend on.
This method returns the derived predicates that the given actions depend on.
- Parameters:
actions – A vector containing the action variants to be analyzed.
- Returns:
A deque of Derived objects representing the derived predicates the actions depend on.
-
void backtrackTraverse(const NodeVariant &start, const std::function<void(const NodeVariant&)> &func) const
-
void backtrackTraverse(const NodeVariant &node, std::unordered_set<NodeVariant> &visited, const std::function<void(const NodeVariant&)> &func) const
-
DerivedResolutionGraph getSubGraphFromNodes(const std::vector<NodeVariant> &nodes) const
Extracts a subgraph from the current DerivedResolutionGraph using the specified nodes.
This method creates and returns a new DerivedResolutionGraph that contains the nodes provided in the input vector and its children nodes.
- Parameters:
nodes – A vector of NodeVariant objects representing the root nodes to obtain the subgraph from.
- Returns:
A DerivedResolutionGraph object representing the subgraph obtained from the input nodes.
-
plansys2::DerivedResolutionGraph pruneGraphToActions(const std::vector<plansys2::ActionVariant> &actions)
Prunes the graph to include only nodes the specified actions depend on.
This function takes a list of actions and returns a new DerivedResolutionGraph that contains only the nodes and edges relevant to those actions. It is useful for focusing the resolution graph on a subset of actions, potentially improving performance.s.
- Parameters:
actions – A vector of ActionVariant objects representing the actions to retain in the pruned graph.
- Returns:
A new DerivedResolutionGraph containing only the nodes the specified actions depend on.
-
void appendActions(const std::vector<plansys2::ActionVariant> &actions)
-
void appendAction(const plansys2::ActionVariant &action)
-
std::vector<std::vector<Derived>> computeSCCsTarjanDerivedPredicates() const
Computes the strongly connected components (SCCs) of the graph.
This function returns the SCCs of the graph using Tarjan’s algorithm. It only includes derived predicates in the SCCs.
- Returns:
std::vector<std::vector<Derived>> A vector of SCCs, each represented as a vector of Derived predicates.
-
void strongConnect(const Derived &node, int ¤t_index, std::unordered_map<Derived, int> &index, std::unordered_map<Derived, int> &lowlink, std::unordered_set<Derived> &on_stack, std::stack<Derived> &stack, std::vector<std::vector<Derived>> &sccs) const
Helper function to compute SCCs.
-
inline const std::unordered_set<NodeVariant> &getNodeOutEdges(const NodeVariant &node)
-
inline const std::unordered_set<NodeVariant> &getNodeInEdges(const NodeVariant &node)
-
inline const std::unordered_set<NodeVariant> &getRoots() const
-
inline const std::unordered_set<NodeVariant> &getNodes() const
-
inline auto getEdgeNumber() const
-
inline auto getNodeNumber() const
-
inline auto getRootNumber() const
-
inline auto getDerivedPredicatesNumber() const
-
inline auto getActionsNumber() const
-
std::vector<std::string> getNodesNames() const
-
std::vector<std::string> getPredicatesNames() const
-
std::vector<std::string> getFunctionsNames() const
-
std::vector<std::string> getDerivedPredicatesNames() const
-
inline std::unordered_set<plansys2::ActionVariant> getActions() const
-
std::vector<std::string> getRootsNames() const
-
std::unordered_set<NodeVariant> getParentNodes(const NodeVariant &node) const
-
std::vector<std::string> getParentNodesNames(const NodeVariant &node) const
-
void exportToDOT(const std::string &filename) const
-
inline void clear()
-
inline bool operator==(const DerivedResolutionGraph &other) const
Friends
- friend struct std::hash< DerivedResolutionGraph >