Class STNBTBuilder

Inheritance Relationships

Base Type

Class Documentation

class STNBTBuilder : public plansys2::BTBuilder

Public Functions

STNBTBuilder()
virtual void initialize(const std::string &bt_action_1 = "", const std::string &bt_action_2 = "", int precision = 3)
virtual std::string get_tree(const plansys2_msgs::msg::Plan &current_plan)
inline virtual Graph::Ptr get_graph()
virtual bool propagate(const Graph::Ptr stn)
virtual std::string get_dotgraph(std::shared_ptr<std::map<std::string, ActionExecutionInfo>> action_map, bool enable_legend = false, bool enable_print_graph = false)

Protected Functions

Graph::Ptr build_stn(const plansys2_msgs::msg::Plan &plan) const
std::string build_bt(const Graph::Ptr stn) const
Graph::Ptr init_graph(const plansys2_msgs::msg::Plan &plan) const
std::vector<ActionStamped> get_plan_actions(const plansys2_msgs::msg::Plan &plan) const
std::set<int> get_happenings(const plansys2_msgs::msg::Plan &plan) const
std::set<int>::iterator get_happening(int time, const std::set<int> &happenings) const
std::set<int>::iterator get_previous(int time, const std::set<int> &happenings) const
std::multimap<int, ActionStamped> get_simple_plan(const plansys2_msgs::msg::Plan &plan) const
std::map<int, StateVec> get_states(const std::set<int> &happenings, const std::multimap<int, ActionStamped> &plan) const
plansys2_msgs::msg::Tree from_state(const std::vector<plansys2::Predicate> &preds, const std::vector<plansys2::Function> &funcs) const
std::vector<Node::Ptr> get_nodes(const ActionStamped &action, const Graph::Ptr graph) const
bool is_match(const Node::Ptr node, const ActionStamped &action) const
std::vector<std::pair<int, ActionStamped>> get_parents(const std::pair<int, ActionStamped> &action, const std::multimap<int, ActionStamped> &plan, const std::set<int> &happenings, const std::map<int, StateVec> &states) const
std::vector<std::pair<int, ActionStamped>> get_satisfy(const std::pair<int, ActionStamped> &action, const std::multimap<int, ActionStamped> &plan, const std::set<int> &happenings, const std::map<int, StateVec> &states) const
std::vector<std::pair<int, ActionStamped>> get_threat(const std::pair<int, ActionStamped> &action, const std::multimap<int, ActionStamped> &plan, const std::set<int> &happenings, const std::map<int, StateVec> &states) const
bool can_apply(const std::pair<int, ActionStamped> &action, const std::multimap<int, ActionStamped> &plan, const int &time, StateVec &state) const
StateVec get_diff(const StateVec &X_1, const StateVec &X_2) const
StateVec get_intersection(const StateVec &X_1, const StateVec &X_2) const
plansys2_msgs::msg::Tree get_conditions(const ActionStamped &action) const
plansys2_msgs::msg::Tree get_effects(const ActionStamped &action) const
void prune_paths(Node::Ptr current, Node::Ptr previous) const
bool check_paths(Node::Ptr current, Node::Ptr previous) const
Eigen::MatrixXd get_distance_matrix(const Graph::Ptr stn) const
void floyd_warshall(Eigen::MatrixXd &dist) const
std::string get_flow(const Node::Ptr node, const Node::Ptr prev_node, std::set<Node::Ptr> &used, const int &level) const
std::string start_execution_block(const Node::Ptr node, const int &l) const
std::string end_execution_block(const Node::Ptr node, const int &l) const
void get_flow_dotgraph(Node::Ptr node, std::set<std::string> &edges)
std::string get_node_dotgraph(Node::Ptr node, std::shared_ptr<std::map<std::string, ActionExecutionInfo>> action_map)
ActionExecutor::Status get_action_status(ActionStamped action, std::shared_ptr<std::map<std::string, ActionExecutionInfo>> action_map)
std::string add_dot_graph_legend(int level_counter, int node_counter)
void print_graph(const plansys2::Graph::Ptr graph) const
void print_node(const Node::Ptr node, int level) const
void print_arcs(const plansys2::Graph::Ptr graph) const
void replace(std::string &str, const std::string &from, const std::string &to) const
bool is_end(const std::tuple<Node::Ptr, double, double> &edge, const ActionStamped &action) const
std::string t(const int &level) const

Protected Attributes

std::shared_ptr<plansys2::DomainExpertClient> domain_client_
std::shared_ptr<plansys2::ProblemExpertClient> problem_client_
Graph::Ptr stn_
std::string bt_start_action_
std::string bt_end_action_
int action_time_precision_