Class ExecutorNode

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::LifecycleNode

Class Documentation

class ExecutorNode : public rclcpp_lifecycle::LifecycleNode

Public Types

using ExecutePlan = plansys2_msgs::action::ExecutePlan
using GoalHandleExecutePlan = rclcpp_action::ServerGoalHandle<ExecutePlan>
using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

Public Functions

ExecutorNode()
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)
CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)
CallbackReturnT on_error(const rclcpp_lifecycle::State &state)
void get_ordered_sub_goals_service_callback(const std::shared_ptr<rmw_request_id_t> request_header, const std::shared_ptr<plansys2_msgs::srv::GetOrderedSubGoals::Request> request, const std::shared_ptr<plansys2_msgs::srv::GetOrderedSubGoals::Response> response)
void get_plan_service_callback(const std::shared_ptr<rmw_request_id_t> request_header, const std::shared_ptr<plansys2_msgs::srv::GetPlan::Request> request, const std::shared_ptr<plansys2_msgs::srv::GetPlan::Response> response)

Protected Functions

std::optional<std::vector<plansys2_msgs::msg::Tree>> getOrderedSubGoals()
rclcpp_action::GoalResponse handle_goal(const rclcpp_action::GoalUUID &uuid, std::shared_ptr<const ExecutePlan::Goal> goal)
rclcpp_action::CancelResponse handle_cancel(const std::shared_ptr<GoalHandleExecutePlan> goal_handle)
void execute(const std::shared_ptr<GoalHandleExecutePlan> goal_handle)
void handle_accepted(const std::shared_ptr<GoalHandleExecutePlan> goal_handle)
std::vector<plansys2_msgs::msg::ActionExecutionInfo> get_feedback_info(std::shared_ptr<std::map<std::string, ActionExecutionInfo>> action_map)
void print_execution_info(std::shared_ptr<std::map<std::string, ActionExecutionInfo>> exec_info)

Protected Attributes

bool cancel_plan_requested_
std::optional<plansys2_msgs::msg::Plan> current_plan_
std::optional<std::vector<plansys2_msgs::msg::Tree>> ordered_sub_goals_
std::string action_bt_xml_
std::string start_action_bt_xml_
std::string end_action_bt_xml_
pluginlib::ClassLoader<plansys2::BTBuilder> bt_builder_loader_
std::shared_ptr<plansys2::DomainExpertClient> domain_client_
std::shared_ptr<plansys2::ProblemExpertClient> problem_client_
std::shared_ptr<plansys2::PlannerClient> planner_client_
rclcpp_lifecycle::LifecyclePublisher<plansys2_msgs::msg::ActionExecutionInfo>::SharedPtr execution_info_pub_
rclcpp_lifecycle::LifecyclePublisher<plansys2_msgs::msg::Plan>::SharedPtr executing_plan_pub_
rclcpp_action::Server<ExecutePlan>::SharedPtr execute_plan_action_server_
rclcpp::Service<plansys2_msgs::srv::GetOrderedSubGoals>::SharedPtr get_ordered_sub_goals_service_
rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::String>::SharedPtr dotgraph_pub_
rclcpp::Service<plansys2_msgs::srv::GetPlan>::SharedPtr get_plan_service_