Class ActionExecutor

Class Documentation

class ActionExecutor

Public Types

enum Status

Values:

enumerator IDLE
enumerator DEALING
enumerator RUNNING
enumerator SUCCESS
enumerator FAILURE
enumerator CANCELLED
using Ptr = std::shared_ptr<ActionExecutor>

Public Functions

explicit ActionExecutor(const std::string &action, rclcpp_lifecycle::LifecycleNode::SharedPtr node)
BT::NodeStatus tick(const rclcpp::Time &now)
void cancel()
BT::NodeStatus get_status()
bool is_finished()
inline Status get_internal_status() const
inline void set_internal_status(Status state)
inline std::string get_action_name() const
inline std::vector<std::string> get_action_params() const
inline rclcpp::Time get_start_time() const
inline rclcpp::Time get_status_time() const
inline std::string get_feedback() const
inline float get_completion() const

Public Members

plansys2_msgs::msg::ActionExecution last_msg

Public Static Functions

static inline Ptr make_shared(const std::string &action, rclcpp_lifecycle::LifecycleNode::SharedPtr node)

Protected Functions

void action_hub_callback(const plansys2_msgs::msg::ActionExecution::SharedPtr msg)
void request_for_performers()
void confirm_performer(const std::string &node_id)
void reject_performer(const std::string &node_id)
std::string get_name(const std::string &action_expr)
std::vector<std::string> get_params(const std::string &action_expr)
void wait_timeout()

Protected Attributes

rclcpp_lifecycle::LifecycleNode::SharedPtr node_
Status state_
rclcpp::Time state_time_
rclcpp::Time start_execution_
std::string action_
std::string action_name_
std::string current_performer_id_
std::vector<std::string> action_params_
std::string feedback_
float completion_
rclcpp_lifecycle::LifecyclePublisher<plansys2_msgs::msg::ActionExecution>::SharedPtr action_hub_pub_
rclcpp::Subscription<plansys2_msgs::msg::ActionExecution>::SharedPtr action_hub_sub_
rclcpp::TimerBase::SharedPtr waiting_timer_