Class SimpleBTBuilder

Inheritance Relationships

Base Type

Class Documentation

class SimpleBTBuilder : public plansys2::BTBuilder

Simple implementation of a behavior tree builder.

Converts a sequential plan into a behavior tree by analyzing action dependencies based on their preconditions and effects, constructing a graph, and then transforming the graph into a behavior tree.

Public Functions

SimpleBTBuilder()

Constructor for SimpleBTBuilder.

Initializes domain and problem clients.

virtual void initialize(const std::string &bt_action_1 = "", const std::string &bt_action_2 = "", int precision = 3)

Initializes the builder with behavior tree templates.

Parameters:
  • bt_action_1[in] XML template for regular actions, default empty.

  • bt_action_2[in] XML template for durative actions, default empty.

  • precision[in] Precision for time calculations, default 3.

virtual std::string get_tree(const plansys2_msgs::msg::Plan &current_plan)

Generates a behavior tree XML from a plan.

Analyzes the plan, constructs an action graph based on dependencies, and converts the graph into a behavior tree XML.

Parameters:

current_plan[in] The plan to transform into a behavior tree.

Returns:

std::string containing the behavior tree XML.

inline virtual Graph::Ptr get_graph()

Not implemented for SimpleBTBuilder.

Returns:

nullptr as this function is not implemented.

inline virtual bool propagate(Graph::Ptr)

Not implemented for SimpleBTBuilder.

Parameters:

graph[in] The graph to propagate constraints through.

Returns:

Always returns true as this function is not implemented.

virtual std::string get_dotgraph(std::shared_ptr<std::map<std::string, ActionExecutionInfo>> action_map, bool enable_legend = false, bool enable_print_graph = false)

Generates a DOT graph representation of the action graph for visualization.

Parameters:
  • action_map[in] Map of action IDs to execution information.

  • enable_legend[in] Whether to include a legend in the graph, default false.

  • enable_print_graph[in] Whether to print the graph to console, default false.

Returns:

std::string containing the DOT graph representation.

Protected Functions

ActionGraph::Ptr get_graph(const plansys2_msgs::msg::Plan &current_plan)

Constructs an action graph from a plan.

Analyzes action dependencies based on preconditions and effects to build a directed acyclic graph.

Parameters:

current_plan[in] The plan to analyze.

Returns:

Shared pointer to the constructed action graph.

std::vector<ActionStamped> get_plan_actions(const plansys2_msgs::msg::Plan &plan)

Extracts action information from a plan.

Parameters:

plan[in] The plan to extract actions from.

Returns:

std::vector<ActionStamped> Vector of ActionStamped objects representing the plan actions.

void prune_backwards(ActionNode::Ptr new_node, ActionNode::Ptr node_satisfy)

Removes redundant incoming edges to a node.

Prunes the graph by removing redundant dependencies.

Parameters:
  • new_node[in] The node being added to the graph.

  • node_satisfy[in] A node that satisfies a requirement of new_node.

void prune_forward(ActionNode::Ptr current, std::list<ActionNode::Ptr> &used_nodes)

Removes redundant outgoing edges from a node.

Parameters:
  • current[in] The node to prune outgoing edges from.

  • used_nodes[inout] List of nodes already processed.

void get_state(const ActionNode::Ptr &node, std::list<ActionNode::Ptr> &used_nodes, std::vector<plansys2::Predicate> &predicates, std::vector<plansys2::Function> &functions) const

Computes the state of the world at a node.

Recursively applies effects of predecessor actions to determine the state at the current node.

Parameters:
  • node[in] The node to compute state for.

  • used_nodes[inout] List of nodes already processed.

  • predicates[out] Resulting predicates at this node.

  • functions[out] Resulting functions at this node.

bool is_action_executable(const ActionStamped &action, std::vector<plansys2::Predicate> &predicates, std::vector<plansys2::Function> &functions) const

Checks if an action is executable in a given state.

Parameters:
  • action[in] The action to check.

  • predicates[in] Current predicates.

  • functions[in] Current functions.

Returns:

True if the action’s requirements are satisfied, false otherwise.

std::list<ActionNode::Ptr> get_roots(std::vector<plansys2::ActionStamped> &action_sequence, std::vector<plansys2::Predicate> &predicates, std::vector<plansys2::Function> &functions, int &node_counter)

Finds root actions that can be executed immediately.

Parameters:
  • action_sequence[inout] Actions to check, executable ones will be removed.

  • predicates[in] Current predicates.

  • functions[in] Current functions.

  • node_counter[inout] Counter for assigning unique node IDs.

Returns:

std::list<ActionNode::Ptr> List of nodes representing executable actions.

ActionNode::Ptr get_node_satisfy(const plansys2_msgs::msg::Tree &requirement, const ActionGraph::Ptr &graph, const ActionNode::Ptr &current)

Finds a node that satisfies a given requirement.

Parameters:
  • requirement[in] The requirement to satisfy.

  • graph[in] The action graph to search.

  • current[in] The current node being processed.

Returns:

A node that satisfies the requirement, or nullptr if none found.

ActionNode::Ptr get_node_satisfy(const plansys2_msgs::msg::Tree &requirement, const ActionNode::Ptr &node, const ActionNode::Ptr &current)

Finds a node that satisfies a given requirement within a subtree.

Parameters:
  • requirement[in] The requirement to satisfy.

  • node[in] The root of the subtree to search.

  • current[in] The current node being processed.

Returns:

A node that satisfies the requirement, or nullptr if none found.

std::list<ActionNode::Ptr> get_node_contradict(const ActionGraph::Ptr &graph, const ActionNode::Ptr &current)

Finds nodes whose execution would be contradicted by the current node.

Parameters:
  • graph[in] The action graph to search.

  • current[in] The current node being processed.

Returns:

List of nodes that would be contradicted.

void get_node_contradict(const ActionNode::Ptr &node, const ActionNode::Ptr &current, std::list<ActionNode::Ptr> &parents)

Recursively finds nodes contradicted by the current node within a subtree.

Parameters:
  • node[in] The root of the subtree to search.

  • current[in] The current node being processed.

  • parents[inout] List to collect contradicted nodes.

void remove_existing_requirements(std::vector<plansys2_msgs::msg::Tree> &requirements, std::vector<plansys2::Predicate> &predicates, std::vector<plansys2::Function> &functions) const

Removes requirements that are already satisfied in the current state.

Parameters:
  • requirements[inout] List of requirements to filter.

  • predicates[in] Current predicates.

  • functions[in] Current functions.

bool is_parallelizable(const plansys2::ActionStamped &action, const std::vector<plansys2::Predicate> &predicates, const std::vector<plansys2::Function> &functions, const std::list<ActionNode::Ptr> &ret) const

Checks if an action can be executed in parallel with a set of other actions.

Parameters:
  • action[in] The action to check.

  • predicates[in] Current predicates.

  • functions[in] Current functions.

  • ret[in] List of actions to check parallelization with.

Returns:

True if the action can be executed in parallel, false otherwise.

std::string get_flow_tree(ActionNode::Ptr node, std::list<std::string> &used_nodes, int level = 0)

Generates the behavior tree XML for a node and its descendants.

Parameters:
  • node[in] The node to process.

  • used_nodes[inout] List of nodes already processed.

  • level[in] Indentation level.

Returns:

std::string containing the behavior tree XML.

void get_flow_dotgraph(ActionNode::Ptr node, std::set<std::string> &edges)

Collects edges for DOT graph visualization.

Parameters:
  • node[in] The node to process.

  • edges[inout] Set to collect edge definitions.

std::string get_node_dotgraph(ActionNode::Ptr node, std::shared_ptr<std::map<std::string, ActionExecutionInfo>> action_map, int level = 0)

Generates DOT graph node definition for a single action node.

Parameters:
  • node[in] The node to generate a definition for.

  • action_map[in] Map of action IDs to execution information.

  • level[in] Indentation level.

Returns:

std::string containing the DOT node definition.

ActionExecutor::Status get_action_status(ActionStamped action, std::shared_ptr<std::map<std::string, ActionExecutionInfo>> action_map)

Gets the execution status of an action.

Parameters:
  • action[in] The action to check.

  • action_map[in] Map of action IDs to execution information.

Returns:

Status of the action.

void addDotGraphLegend(std::stringstream &ss, int tab_level, int level_counter, int node_counter)

Adds a legend to the DOT graph.

Parameters:
  • ss[inout] Stream to write the legend to.

  • tab_level[in] Indentation level.

  • level_counter[in] Counter for cluster IDs.

  • node_counter[in] Counter for node IDs.

std::string t(int level)

Helper function to generate indentation.

Parameters:

level[in] Indentation level.

Returns:

std::string with the specified number of tabs.

std::string execution_block(const ActionNode::Ptr &node, int l)

Generates the behavior tree XML for executing a single action.

Parameters:
  • node[in] The action node.

  • l[in] Indentation level.

Returns:

std::string containing the behavior tree XML.

void print_node(const ActionNode::Ptr &node, int level, std::set<ActionNode::Ptr> &used_nodes) const

Prints a node and its descendants to stderr for debugging.

Parameters:
  • node[in] The node to print.

  • level[in] Indentation level.

  • used_nodes[inout] Set of nodes already processed.

void print_graph(const plansys2::ActionGraph::Ptr &graph) const

Prints the entire action graph to stderr for debugging.

Parameters:

graph[in] The graph to print.

void print_node_csv(const ActionNode::Ptr &node, uint32_t root_num) const

Prints a node in CSV format to stderr for debugging.

Parameters:
  • node[in] The node to print.

  • root_num[in] The root number this node belongs to.

void print_graph_csv(const plansys2::ActionGraph::Ptr &graph) const

Prints the entire action graph in CSV format to stderr for debugging.

Parameters:

graph[in] The graph to print.

void get_node_tabular(const plansys2::ActionNode::Ptr &node, uint32_t root_num, std::vector<std::tuple<uint32_t, uint32_t, uint32_t, std::string>> &graph) const

Collects node information in a tabular format.

Parameters:
  • node[in] The node to process.

  • root_num[in] The root number this node belongs to.

  • graph[out] Vector to collect node information.

std::vector<std::tuple<uint32_t, uint32_t, uint32_t, std::string>> get_graph_tabular(const plansys2::ActionGraph::Ptr &graph) const

Gets the entire action graph in a tabular format.

Parameters:

graph[in] The graph to process.

Returns:

Vector of tuples containing node information.

Protected Attributes

std::shared_ptr<plansys2::DomainExpertClient> domain_client_
std::shared_ptr<plansys2::ProblemExpertClient> problem_client_
ActionGraph::Ptr graph_
std::string bt_
std::string bt_action_