C++ YASMIN (Yet Another State MachINe)
|
A state class for handling ROS 2 action client operations. More...
#include <action_state.hpp>
Public Member Functions | |
ActionState (std::string action_name, CreateGoalHandler create_goal_handler, std::set< std::string > outcomes, int timeout=-1.0) | |
Construct an ActionState with a specific action name and goal handler. | |
ActionState (std::string action_name, CreateGoalHandler create_goal_handler, ResultHandler result_handler=nullptr, FeedbackHandler feedback_handler=nullptr, int timeout=-1.0) | |
Construct an ActionState with result and feedback handlers. | |
ActionState (std::string action_name, CreateGoalHandler create_goal_handler, std::set< std::string > outcomes, ResultHandler result_handler=nullptr, FeedbackHandler feedback_handler=nullptr, int timeout=-1.0) | |
Construct an ActionState with outcomes and handlers. | |
ActionState (const rclcpp::Node::SharedPtr &node, std::string action_name, CreateGoalHandler create_goal_handler, std::set< std::string > outcomes, ResultHandler result_handler=nullptr, FeedbackHandler feedback_handler=nullptr, int timeout=-1.0) | |
Construct an ActionState with a specified node and action name. | |
void | cancel_state () |
Cancel the current action state. | |
void | cancel_done () |
Notify that the action cancellation has completed. | |
std::string | execute (std::shared_ptr< yasmin::blackboard::Blackboard > blackboard) |
Execute the action and return the outcome. | |
Public Member Functions inherited from yasmin::State | |
State (std::set< std::string > outcomes) | |
Constructs a State with a set of possible outcomes. | |
std::string | operator() (std::shared_ptr< blackboard::Blackboard > blackboard) |
Executes the state and returns the outcome. | |
bool | is_canceled () const |
Checks if the state has been canceled. | |
bool | is_running () const |
Checks if the state is currently running. | |
std::set< std::string > const & | get_outcomes () |
Gets the set of possible outcomes for this state. | |
virtual std::string | to_string () |
Converts the state to a string representation. | |
Private Types | |
using | Goal = typename ActionT::Goal |
Alias for the action goal type. | |
using | Result = typename ActionT::Result::SharedPtr |
Alias for the action result type. | |
using | Feedback = typename ActionT::Feedback |
Alias for the action feedback type. | |
using | SendGoalOptions |
Options for sending goals. | |
using | ActionClient = typename rclcpp_action::Client<ActionT>::SharedPtr |
Shared pointer type for the action client. | |
using | GoalHandle = rclcpp_action::ClientGoalHandle<ActionT> |
Handle for the action goal. | |
using | CreateGoalHandler |
Function type for creating a goal. | |
using | ResultHandler |
Function type for handling results. | |
using | FeedbackHandler |
Function type for handling feedback. | |
Private Member Functions | |
void | goal_response_callback (const typename GoalHandle::SharedPtr &goal_handle) |
Callback for handling the goal response. | |
void | result_callback (const typename GoalHandle::WrappedResult &result) |
Callback for handling the result of the action. | |
Private Attributes | |
rclcpp::Node::SharedPtr | node_ |
Shared pointer to the ROS 2 node. | |
std::string | action_name |
Name of the action to communicate with. | |
ActionClient | action_client |
Shared pointer to the action client. | |
std::condition_variable | action_done_cond |
Condition variable for action completion. | |
std::mutex | action_done_mutex |
Mutex for protecting action completion. | |
std::condition_variable | action_cancel_cond |
Condition variable for action cancellation. | |
std::mutex | action_cancel_mutex |
Mutex for protecting action cancellation. | |
Result | action_result |
Shared pointer to the action result. | |
rclcpp_action::ResultCode | action_status |
Status of the action execution. | |
std::shared_ptr< GoalHandle > | goal_handle |
Handle for the current goal. | |
std::mutex | goal_handle_mutex |
Mutex for protecting access to the goal handle. | |
CreateGoalHandler | create_goal_handler |
Handler function for creating goals. | |
ResultHandler | result_handler |
Handler function for processing results. | |
FeedbackHandler | feedback_handler |
Handler function for processing feedback. | |
int | timeout |
Maximum time to wait for the action server. | |
Additional Inherited Members | |
Protected Attributes inherited from yasmin::State | |
std::set< std::string > | outcomes |
The possible outcomes of this state. | |
A state class for handling ROS 2 action client operations.
This class encapsulates the behavior of a ROS 2 action client within a YASMIN state. It allows the creation and management of goals, feedback, and results associated with an action server.
ActionT | The type of the action this state will interface with. |
|
private |
Shared pointer type for the action client.
|
private |
Function type for creating a goal.
|
private |
Alias for the action feedback type.
|
private |
Function type for handling feedback.
|
private |
Alias for the action goal type.
|
private |
Handle for the action goal.
|
private |
Alias for the action result type.
|
private |
Function type for handling results.
|
private |
Options for sending goals.
|
inline |
Construct an ActionState with a specific action name and goal handler.
This constructor initializes the action state with a specified action name, goal handler, and optional timeout.
action_name | The name of the action to communicate with. |
create_goal_handler | A function that creates a goal for the action. |
outcomes | A set of possible outcomes for this action state. |
timeout | (Optional) The maximum time to wait for the action server. Default is -1 (no timeout). |
std::invalid_argument | if create_goal_handler is nullptr. |
|
inline |
Construct an ActionState with result and feedback handlers.
This constructor allows the specification of result and feedback handlers.
action_name | The name of the action to communicate with. |
create_goal_handler | A function that creates a goal for the action. |
result_handler | (Optional) A function to handle the result of the action. |
feedback_handler | (Optional) A function to handle feedback from the action. |
timeout | (Optional) The maximum time to wait for the action server. Default is -1 (no timeout). |
std::invalid_argument | if create_goal_handler is nullptr. |
|
inline |
Construct an ActionState with outcomes and handlers.
This constructor allows specifying outcomes along with handlers for results and feedback.
action_name | The name of the action to communicate with. |
create_goal_handler | A function that creates a goal for the action. |
outcomes | A set of possible outcomes for this action state. |
result_handler | (Optional) A function to handle the result of the action. |
feedback_handler | (Optional) A function to handle feedback from the action. |
timeout | (Optional) The maximum time to wait for the action server. Default is -1 (no timeout). |
std::invalid_argument | if create_goal_handler is nullptr. |
|
inline |
Construct an ActionState with a specified node and action name.
This constructor allows specifying a ROS 2 node in addition to the action name and goal handler.
node | A shared pointer to the ROS 2 node. |
action_name | The name of the action to communicate with. |
create_goal_handler | A function that creates a goal for the action. |
outcomes | A set of possible outcomes for this action state. |
result_handler | (Optional) A function to handle the result of the action. |
feedback_handler | (Optional) A function to handle feedback from the action. |
timeout | (Optional) The maximum time to wait for the action server. Default is -1 (no timeout). |
std::invalid_argument | if create_goal_handler is nullptr. |
|
inline |
Notify that the action cancellation has completed.
This function is called to notify that the action cancellation process has finished.
|
inlinevirtual |
Cancel the current action state.
This function cancels the ongoing action and waits for the cancellation to complete.
Reimplemented from yasmin::State.
|
inlinevirtual |
Execute the action and return the outcome.
This function creates a goal using the provided goal handler, sends the goal to the action server, and waits for the result or feedback.
blackboard | A shared pointer to the blackboard used for communication. |
Possible outcomes include:
basic_outcomes::SUCCEED
: The action succeeded.basic_outcomes::ABORT
: The action was aborted.basic_outcomes::CANCEL
: The action was canceled.basic_outcomes::TIMEOUT
: The action server was not available in time. Reimplemented from yasmin::State.
|
inlineprivate |
Callback for handling the goal response.
This function is called when a response for the goal is received.
goal_handle | A shared pointer to the goal handle. |
|
inlineprivate |
Callback for handling the result of the action.
This function is called when the action result is available.
result | The wrapped result of the action. |
|
private |
Condition variable for action cancellation.
|
private |
Mutex for protecting action cancellation.
|
private |
Shared pointer to the action client.
|
private |
Condition variable for action completion.
|
private |
Mutex for protecting action completion.
|
private |
Name of the action to communicate with.
|
private |
Shared pointer to the action result.
|
private |
Status of the action execution.
|
private |
Handler function for creating goals.
|
private |
Handler function for processing feedback.
|
private |
Handle for the current goal.
|
private |
Mutex for protecting access to the goal handle.
|
private |
Shared pointer to the ROS 2 node.
|
private |
Handler function for processing results.
|
private |
Maximum time to wait for the action server.