C++ YASMIN (Yet Another State MachINe)
Loading...
Searching...
No Matches
yasmin_ros::ActionState< ActionT > Class Template Reference

A state class for handling ROS 2 action client operations. More...

#include <action_state.hpp>

Inheritance diagram for yasmin_ros::ActionState< ActionT >:
Collaboration diagram for yasmin_ros::ActionState< ActionT >:

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< GoalHandlegoal_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.
 

Detailed Description

template<typename ActionT>
class yasmin_ros::ActionState< ActionT >

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.

Template Parameters
ActionTThe type of the action this state will interface with.

Member Typedef Documentation

◆ ActionClient

template<typename ActionT >
using yasmin_ros::ActionState< ActionT >::ActionClient = typename rclcpp_action::Client<ActionT>::SharedPtr
private

Shared pointer type for the action client.

◆ CreateGoalHandler

template<typename ActionT >
using yasmin_ros::ActionState< ActionT >::CreateGoalHandler
private
Initial value:
std::function<Goal(std::shared_ptr<yasmin::blackboard::Blackboard>)>
typename ActionT::Goal Goal
Alias for the action goal type.
Definition action_state.hpp:48

Function type for creating a goal.

◆ Feedback

template<typename ActionT >
using yasmin_ros::ActionState< ActionT >::Feedback = typename ActionT::Feedback
private

Alias for the action feedback type.

◆ FeedbackHandler

template<typename ActionT >
using yasmin_ros::ActionState< ActionT >::FeedbackHandler
private
Initial value:
std::function<void(std::shared_ptr<yasmin::blackboard::Blackboard>,
std::shared_ptr<const Feedback>)>

Function type for handling feedback.

◆ Goal

template<typename ActionT >
using yasmin_ros::ActionState< ActionT >::Goal = typename ActionT::Goal
private

Alias for the action goal type.

◆ GoalHandle

template<typename ActionT >
using yasmin_ros::ActionState< ActionT >::GoalHandle = rclcpp_action::ClientGoalHandle<ActionT>
private

Handle for the action goal.

◆ Result

template<typename ActionT >
using yasmin_ros::ActionState< ActionT >::Result = typename ActionT::Result::SharedPtr
private

Alias for the action result type.

◆ ResultHandler

template<typename ActionT >
using yasmin_ros::ActionState< ActionT >::ResultHandler
private
Initial value:
std::function<std::string(
std::shared_ptr<yasmin::blackboard::Blackboard>, Result)>
typename ActionT::Result::SharedPtr Result
Alias for the action result type.
Definition action_state.hpp:50

Function type for handling results.

◆ SendGoalOptions

template<typename ActionT >
using yasmin_ros::ActionState< ActionT >::SendGoalOptions
private
Initial value:
typename rclcpp_action::Client<ActionT>::SendGoalOptions

Options for sending goals.

Constructor & Destructor Documentation

◆ ActionState() [1/4]

template<typename ActionT >
yasmin_ros::ActionState< ActionT >::ActionState ( std::string action_name,
CreateGoalHandler create_goal_handler,
std::set< std::string > outcomes,
int timeout = -1.0 )
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.

Parameters
action_nameThe name of the action to communicate with.
create_goal_handlerA function that creates a goal for the action.
outcomesA set of possible outcomes for this action state.
timeout(Optional) The maximum time to wait for the action server. Default is -1 (no timeout).
Exceptions
std::invalid_argumentif create_goal_handler is nullptr.

◆ ActionState() [2/4]

template<typename ActionT >
yasmin_ros::ActionState< ActionT >::ActionState ( std::string action_name,
CreateGoalHandler create_goal_handler,
ResultHandler result_handler = nullptr,
FeedbackHandler feedback_handler = nullptr,
int timeout = -1.0 )
inline

Construct an ActionState with result and feedback handlers.

This constructor allows the specification of result and feedback handlers.

Parameters
action_nameThe name of the action to communicate with.
create_goal_handlerA 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).
Exceptions
std::invalid_argumentif create_goal_handler is nullptr.

◆ ActionState() [3/4]

template<typename ActionT >
yasmin_ros::ActionState< ActionT >::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 )
inline

Construct an ActionState with outcomes and handlers.

This constructor allows specifying outcomes along with handlers for results and feedback.

Parameters
action_nameThe name of the action to communicate with.
create_goal_handlerA function that creates a goal for the action.
outcomesA 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).
Exceptions
std::invalid_argumentif create_goal_handler is nullptr.

◆ ActionState() [4/4]

template<typename ActionT >
yasmin_ros::ActionState< ActionT >::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 )
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.

Parameters
nodeA shared pointer to the ROS 2 node.
action_nameThe name of the action to communicate with.
create_goal_handlerA function that creates a goal for the action.
outcomesA 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).
Exceptions
std::invalid_argumentif create_goal_handler is nullptr.

Member Function Documentation

◆ cancel_done()

template<typename ActionT >
void yasmin_ros::ActionState< ActionT >::cancel_done ( )
inline

Notify that the action cancellation has completed.

This function is called to notify that the action cancellation process has finished.

◆ cancel_state()

template<typename ActionT >
void yasmin_ros::ActionState< ActionT >::cancel_state ( )
inlinevirtual

Cancel the current action state.

This function cancels the ongoing action and waits for the cancellation to complete.

Reimplemented from yasmin::State.

◆ execute()

template<typename ActionT >
std::string yasmin_ros::ActionState< ActionT >::execute ( std::shared_ptr< yasmin::blackboard::Blackboard > blackboard)
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.

Parameters
blackboardA shared pointer to the blackboard used for communication.
Returns
A string representing the outcome of the action execution.

Possible outcomes include:

Reimplemented from yasmin::State.

◆ goal_response_callback()

template<typename ActionT >
void yasmin_ros::ActionState< ActionT >::goal_response_callback ( const typename GoalHandle::SharedPtr & goal_handle)
inlineprivate

Callback for handling the goal response.

This function is called when a response for the goal is received.

Parameters
goal_handleA shared pointer to the goal handle.

◆ result_callback()

template<typename ActionT >
void yasmin_ros::ActionState< ActionT >::result_callback ( const typename GoalHandle::WrappedResult & result)
inlineprivate

Callback for handling the result of the action.

This function is called when the action result is available.

Parameters
resultThe wrapped result of the action.

Member Data Documentation

◆ action_cancel_cond

template<typename ActionT >
std::condition_variable yasmin_ros::ActionState< ActionT >::action_cancel_cond
private

Condition variable for action cancellation.

◆ action_cancel_mutex

template<typename ActionT >
std::mutex yasmin_ros::ActionState< ActionT >::action_cancel_mutex
private

Mutex for protecting action cancellation.

◆ action_client

template<typename ActionT >
ActionClient yasmin_ros::ActionState< ActionT >::action_client
private

Shared pointer to the action client.

◆ action_done_cond

template<typename ActionT >
std::condition_variable yasmin_ros::ActionState< ActionT >::action_done_cond
private

Condition variable for action completion.

◆ action_done_mutex

template<typename ActionT >
std::mutex yasmin_ros::ActionState< ActionT >::action_done_mutex
private

Mutex for protecting action completion.

◆ action_name

template<typename ActionT >
std::string yasmin_ros::ActionState< ActionT >::action_name
private

Name of the action to communicate with.

◆ action_result

template<typename ActionT >
Result yasmin_ros::ActionState< ActionT >::action_result
private

Shared pointer to the action result.

◆ action_status

template<typename ActionT >
rclcpp_action::ResultCode yasmin_ros::ActionState< ActionT >::action_status
private

Status of the action execution.

◆ create_goal_handler

template<typename ActionT >
CreateGoalHandler yasmin_ros::ActionState< ActionT >::create_goal_handler
private

Handler function for creating goals.

◆ feedback_handler

template<typename ActionT >
FeedbackHandler yasmin_ros::ActionState< ActionT >::feedback_handler
private

Handler function for processing feedback.

◆ goal_handle

template<typename ActionT >
std::shared_ptr<GoalHandle> yasmin_ros::ActionState< ActionT >::goal_handle
private

Handle for the current goal.

◆ goal_handle_mutex

template<typename ActionT >
std::mutex yasmin_ros::ActionState< ActionT >::goal_handle_mutex
private

Mutex for protecting access to the goal handle.

◆ node_

template<typename ActionT >
rclcpp::Node::SharedPtr yasmin_ros::ActionState< ActionT >::node_
private

Shared pointer to the ROS 2 node.

◆ result_handler

template<typename ActionT >
ResultHandler yasmin_ros::ActionState< ActionT >::result_handler
private

Handler function for processing results.

◆ timeout

template<typename ActionT >
int yasmin_ros::ActionState< ActionT >::timeout
private

Maximum time to wait for the action server.


The documentation for this class was generated from the following file: