Class ActionExecutor
Defined in File ActionExecutor.hpp
Class Documentation
-
class ActionExecutor
Class that manages the execution of a PDDL action by communicating with action performers.
This class handles the lifecycle of action execution by sending requests to appropriate action performers, monitoring their progress, and reporting completion status. It maintains state information about the execution and communicates over the actions_hub topic.
Public Types
-
enum Status
Status enumeration representing the action execution state.
Values:
-
enumerator IDLE
-
enumerator DEALING
-
enumerator RUNNING
-
enumerator SUCCESS
-
enumerator FAILURE
-
enumerator CANCELLED
-
enumerator IDLE
-
using Ptr = std::shared_ptr<ActionExecutor>
Public Functions
Constructor for the ActionExecutor.
- Parameters:
action – [in] The action expression to execute (in PDDL format).
node – [in] The lifecycle node used for ROS communications.
-
~ActionExecutor()
Destructor for the ActionExecutor.
-
BT::NodeStatus tick(const rclcpp::Time &now)
Process one execution cycle for the action.
Advances the state machine based on the current state:
IDLE → DEALING: sends a request for performers
DEALING: checks for timeout
RUNNING: allows feedback to be processed
- Parameters:
now – [in] Current ROS time.
- Returns:
BT::NodeStatus BehaviorTree status corresponding to the current execution state.
-
void cancel()
Cancel the action execution.
Sets the state to CANCELLED and sends a cancellation message to the performer.
-
BT::NodeStatus get_status()
Get the current status as a BehaviorTree node status.
- Returns:
BT::NodeStatus The current status as a BehaviorTree node status.
-
bool is_finished()
Check if the action execution has finished.
- Returns:
true if the action has succeeded or failed, false otherwise.
-
inline Status get_internal_status() const
Get the internal execution status.
- Returns:
Status The current status enum value.
-
inline void set_internal_status(Status state)
Set the internal execution status.
- Parameters:
state – [in] The new status to set.
-
inline std::string get_action_name() const
Get the name of the action being executed.
- Returns:
std::string The action name.
-
inline std::vector<std::string> get_action_params() const
Get the parameters of the action being executed.
- Returns:
std::vector<std::string> Vector of parameter strings.
-
inline rclcpp::Time get_start_time() const
Get the time when the action execution started.
- Returns:
rclcpp::Time The start time of the execution.
-
inline rclcpp::Time get_current_time() const
Get the current ROS time from the node.
- Returns:
rclcpp::Time Current ROS time.
-
inline rclcpp::Time get_status_time() const
Get the time of the last state change.
- Returns:
ROS time of the last state change.
-
inline std::string get_feedback() const
Get the current feedback from the action performer.
- Returns:
std::string containing the feedback message.
-
inline float get_completion() const
Get the completion percentage of the action.
- Returns:
float Completion percentage (0.0 to 1.0).
-
void clean_up()
Clean up resources used by the executor.
Public Members
-
plansys2_msgs::msg::ActionExecution::SharedPtr last_msg_
Public Static Functions
Factory method to create a shared pointer to an ActionExecutor.
- Parameters:
action – [in] The action expression to execute (in PDDL format).
node – [in] The lifecycle node used for ROS communications.
- Returns:
Shared pointer to the newly created ActionExecutor.
Protected Functions
Process messages from the actions hub.
Handles different message types:
RESPONSE: From performers accepting the request
FEEDBACK: Updates on execution progress
FINISH: Final completion status
- Parameters:
msg – [in] The action execution message received.
-
void request_for_performers()
Send a request for performers to execute this action.
Publishes a REQUEST message to the actions_hub topic.
-
void confirm_performer(const std::string &node_id)
Confirm a performer for this action.
Sends a CONFIRM message to the selected performer.
- Parameters:
node_id – [in] ID of the performer to confirm.
-
void reject_performer(const std::string &node_id)
Reject a performer for this action.
Sends a REJECT message to the performer.
- Parameters:
node_id – [in] ID of the performer to reject.
-
std::string get_name(const std::string &action_expr)
Extract the action name from an action expression.
Parses a PDDL action expression to extract just the action name.
- Parameters:
action_expr – [in] The action expression to parse.
- Returns:
std::string The extracted action name.
-
std::vector<std::string> get_params(const std::string &action_expr)
Extract parameters from an action expression.
Parses a PDDL action expression to extract the parameter values.
- Parameters:
action_expr – [in] The action expression to parse.
- Returns:
std::vector<std::string> Vector of extracted parameter strings.
-
void wait_timeout()
Timeout handler for performer requests.
Called when no performer responds in time, logs a warning and retries.
Protected Attributes
-
rclcpp_lifecycle::LifecycleNode::SharedPtr node_
-
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_
-
enum Status