Class ActionExecutorClient

Inheritance Relationships

Base Type

  • public rclcpp_cascade_lifecycle::CascadeLifecycleNode

Class Documentation

class ActionExecutorClient : public rclcpp_cascade_lifecycle::CascadeLifecycleNode

Public Types

using Ptr = std::shared_ptr<ActionExecutorClient>

Public Functions

ActionExecutorClient(const std::string &node_name, const std::chrono::nanoseconds &rate)
inline rclcpp::Time get_start_time() const
inline plansys2_msgs::msg::ActionPerformerStatus get_internal_status() const

Public Static Functions

static inline Ptr make_shared(const std::string &node_name, const std::chrono::nanoseconds &rate)

Protected Types

using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

Protected Functions

inline virtual void do_work()
inline const std::vector<std::string> &get_arguments() const
inline const std::string get_action_name() const
virtual CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
virtual CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
virtual CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
void action_hub_callback(const plansys2_msgs::msg::ActionExecution::SharedPtr msg)
bool should_execute(const std::string &action, const std::vector<std::string> &args)
void send_response(const plansys2_msgs::msg::ActionExecution::SharedPtr msg)
void send_feedback(float completion, const std::string &status = "")
void finish(bool success, float completion, const std::string &status = "")

Protected Attributes

std::chrono::nanoseconds rate_
std::string action_managed_
bool commited_
std::vector<std::string> current_arguments_
std::vector<std::string> specialized_arguments_
rclcpp_lifecycle::LifecyclePublisher<plansys2_msgs::msg::ActionExecution>::SharedPtr action_hub_pub_
rclcpp::Subscription<plansys2_msgs::msg::ActionExecution>::SharedPtr action_hub_sub_
rclcpp::TimerBase::SharedPtr timer_
rclcpp_lifecycle::LifecyclePublisher<plansys2_msgs::msg::ActionPerformerStatus>::SharedPtr status_pub_
rclcpp::TimerBase::SharedPtr hearbeat_pub_
plansys2_msgs::msg::ActionPerformerStatus status_
rclcpp::Time start_time_