Class ActionExecutorClient
Defined in File ActionExecutorClient.hpp
Inheritance Relationships
Base Type
public rclcpp_cascade_lifecycle::CascadeLifecycleNode
Class Documentation
-
class ActionExecutorClient : public rclcpp_cascade_lifecycle::CascadeLifecycleNode
Base class for implementing action executors in the planning system.
ActionExecutorClient provides a framework for executing PDDL actions in the real world. It handles the communication with the executor node, manages the action lifecycle, and provides feedback about the execution progress.
Public Types
-
using Ptr = std::shared_ptr<ActionExecutorClient>
Public Functions
-
explicit ActionExecutorClient(const std::string &node_name)
Constructor for the ActionExecutorClient.
- Parameters:
node_name – [in] Name for the ROS node.
-
ActionExecutorClient(const std::string &node_name, const std::chrono::nanoseconds &rate)
Constructor for the ActionExecutorClient.
- Parameters:
node_name – [in] Name for the ROS node.
rate – [in] Execution rate for periodic work.
-
inline rclcpp::Time get_start_time() const
Get the time when the action execution started.
- Returns:
rclcpp::TimeThe ROS time when action execution was activated.
-
inline plansys2_msgs::msg::ActionPerformerStatus get_internal_status() const
Get the current internal status of the action executor.
- Returns:
plansys2_msgs::msg::ActionPerformerStatus Current status message with state, timestamp, action and specialized arguments.
Public Static Functions
Factory method to create a shared pointer to an ActionExecutorClient.
- Parameters:
node_name – [in] Name for the ROS node.
- Returns:
Shared pointer to the newly created ActionExecutorClient.
Protected Functions
-
inline virtual void do_work()
Main work method that derived classes should implement.
This method is called periodically at the rate specified in the constructor. Derived classes should implement this method to perform the actual execution of the action and report progress.
-
inline const std::vector<std::string> &get_arguments() const
Get the arguments for the current action execution.
- Returns:
Reference to the vector of arguments.
-
inline const std::string get_action_name() const
Get the name of the action this executor manages.
- Returns:
std::stringThe action name.
-
virtual CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
Configures the node.
- Parameters:
state – [in] The current lifecycle state.
- Returns:
SUCCESS if configuration is successful, FAILURE otherwise.
-
virtual CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
Activates the node.
- Parameters:
state – [in] The current lifecycle state.
- Returns:
SUCCESS if activation is successful, FAILURE otherwise.
-
virtual CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
Deactivates the node.
- Parameters:
state – [in] The current lifecycle state.
- Returns:
SUCCESS if deactivation is successful, FAILURE otherwise.
Process messages from the actions hub.
Handles REQUEST, CONFIRM, REJECT, and CANCEL messages, managing the action execution lifecycle accordingly.
- Parameters:
msg – [in] The action execution message received.
-
bool should_execute(const std::string &action, const std::vector<std::string> &args)
Check if this executor should execute the given action.
Verifies that the action name matches and that any specialized arguments are compatible with the requested arguments.
- Parameters:
action – [in] The action name to check.
args – [in] The arguments to check.
- Returns:
True if this executor should handle the action, false otherwise.
Send a response to a request message.
Indicates that this executor is willing to execute the requested action.
- Parameters:
msg – [in] The original request message.
-
void send_feedback(float completion, const std::string &status = "")
Send feedback about the action execution progress.
- Parameters:
completion – [in] Percentage of completion (0.0 to 1.0).
status – [in] Optional status message describing the current state.
-
void finish(bool success, float completion, const std::string &status = "")
Finish the action execution.
Deactivates the executor if active and sends a FINISH message to indicate completion or failure.
- Parameters:
success – [in] Whether the action was successful.
completion – [in] Final completion percentage (typically 1.0 for success).
status – [in] Optional status message describing the final state.
Protected Attributes
-
std::chrono::nanoseconds period_
-
std::string action_managed_
-
bool committed_
-
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_
-
using Ptr = std::shared_ptr<ActionExecutorClient>