Template Class ActionState

Inheritance Relationships

Base Type

  • public yasmin::State

Class Documentation

template<typename ActionT>
class ActionState : public yasmin::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.

Template Parameters:

ActionT – The type of the action this state will interface with.

Public Functions

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

This constructor initializes the action state with a specified action name, goal handler, and optional timeout.

Parameters:
  • 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).

Throws:

std::invalid_argument – if create_goal_handler is nullptr.

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

This constructor allows the specification of result and feedback handlers.

Parameters:
  • 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).

Throws:

std::invalid_argument – if create_goal_handler is nullptr.

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

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

Parameters:
  • 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).

Throws:

std::invalid_argument – if create_goal_handler is nullptr.

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

This constructor allows specifying a ROS 2 node in addition to the action name and goal handler.

Parameters:
  • 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).

Throws:

std::invalid_argument – if create_goal_handler is nullptr.

inline void cancel_state()

Cancel the current action state.

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

inline void cancel_done()

Notify that the action cancellation has completed.

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

inline std::string execute(std::shared_ptr<yasmin::blackboard::Blackboard> blackboard)

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.

Possible outcomes include:

Parameters:

blackboard – A shared pointer to the blackboard used for communication.

Returns:

A string representing the outcome of the action execution.