16#ifndef YASMIN_ROS__ACTION_STATE_HPP
17#define YASMIN_ROS__ACTION_STATE_HPP
19#include <condition_variable>
25#include "rclcpp/rclcpp.hpp"
26#include "rclcpp_action/rclcpp_action.hpp"
35using namespace std::placeholders;
50 using Goal =
typename ActionT::Goal;
52 using Result =
typename ActionT::Result::SharedPtr;
58 typename rclcpp_action::Client<ActionT>::SendGoalOptions;
60 using ActionClient =
typename rclcpp_action::Client<ActionT>::SharedPtr;
62 using GoalHandle = rclcpp_action::ClientGoalHandle<ActionT>;
65 std::function<
Goal(std::shared_ptr<yasmin::blackboard::Blackboard>)>;
68 std::shared_ptr<yasmin::blackboard::Blackboard>,
Result)>;
71 std::function<void(std::shared_ptr<yasmin::blackboard::Blackboard>,
72 std::shared_ptr<const Feedback>)>;
124 const std::set<std::string> &
outcomes,
125 rclcpp::CallbackGroup::SharedPtr callback_group =
nullptr,
185 const std::set<std::string> &
outcomes,
220 const std::set<std::string> &
outcomes,
223 rclcpp::CallbackGroup::SharedPtr callback_group =
nullptr,
233 if (this->wait_timeout > 0 || this->response_timeout > 0) {
238 for (
const std::string &outcome :
outcomes) {
239 this->outcomes.insert(outcome);
243 if (node ==
nullptr) {
253 throw std::invalid_argument(
"create_goal_handler is needed");
302 execute(std::shared_ptr<yasmin::blackboard::Blackboard> blackboard) {
313 std::chrono::duration<int64_t, std::ratio<1>>(this->wait_timeout))) {
321 this->maximum_retry);
329 send_goal_options.goal_response_callback =
332 send_goal_options.result_callback =
335 if (this->feedback_handler) {
336 send_goal_options.feedback_callback =
337 [
this, blackboard](
typename GoalHandle::SharedPtr,
338 std::shared_ptr<const Feedback> feedback) {
344 this->
action_client->async_send_goal(goal, send_goal_options);
346 if (this->response_timeout > 0) {
348 lock, std::chrono::seconds(this->response_timeout)) ==
349 std::cv_status::timeout) {
351 "Timeout reached while waiting for response from action '%s'",
357 this->maximum_retry);
371 case rclcpp_action::ResultCode::CANCELED:
374 case rclcpp_action::ResultCode::ABORTED:
377 case rclcpp_action::ResultCode::SUCCEEDED:
432#if __has_include("rclcpp/version.h")
433#include "rclcpp/version.h"
434#if RCLCPP_VERSION_GTE(2, 4, 3)
444 std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
456 std::shared_future<typename GoalHandle::SharedPtr> future) {
457 std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
458 this->goal_handle = future.get();
470 std::shared_future<typename GoalHandle::SharedPtr> future) {
471 std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
472 this->goal_handle = future.get();
484 this->action_result = result.result;
485 this->action_status = result.code;
486 this->action_done_cond.notify_one();
Represents a state in a state machine.
Definition state.hpp:53
bool is_canceled() const
Checks if the state has been canceled.
Definition state.cpp:41
State(const std::set< std::string > &outcomes)
Constructs a State with a set of possible outcomes.
Definition state.cpp:27
std::set< std::string > outcomes
The possible outcomes of this state.
Definition state.hpp:57
virtual void cancel_state()
Cancels the current state execution.
Definition state.hpp:133
void result_callback(const typename GoalHandle::WrappedResult &result)
Callback for handling the result of the action.
Definition action_state.hpp:483
int wait_timeout
Maximum time to wait for the action server.
Definition action_state.hpp:426
std::condition_variable action_done_cond
Condition variable for action completion.
Definition action_state.hpp:400
ActionState(const std::string &action_name, CreateGoalHandler create_goal_handler, const std::set< std::string > &outcomes, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr, int wait_timeout=-1, int response_timeout=-1, int maximum_retry=3)
Construct an ActionState with a specific action name and goal handler.
Definition action_state.hpp:122
std::mutex action_cancel_mutex
Mutex for protecting action cancellation.
Definition action_state.hpp:406
rclcpp_action::ClientGoalHandle< ActionT > GoalHandle
Handle for the action goal.
Definition action_state.hpp:62
ActionState(const std::string &action_name, CreateGoalHandler create_goal_handler, const std::set< std::string > &outcomes, ResultHandler result_handler=nullptr, FeedbackHandler feedback_handler=nullptr, int wait_timeout=-1, int response_timeout=-1, int maximum_retry=3)
Construct an ActionState with outcomes and handlers.
Definition action_state.hpp:183
std::function< std::string( std::shared_ptr< yasmin::blackboard::Blackboard >, Result)> ResultHandler
Function type for handling results.
Definition action_state.hpp:67
void cancel_done()
Notify that the action cancellation has completed.
Definition action_state.hpp:283
Result action_result
Shared pointer to the action result.
Definition action_state.hpp:409
std::condition_variable action_cancel_cond
Condition variable for action cancellation.
Definition action_state.hpp:404
typename ActionT::Feedback Feedback
Alias for the action feedback type.
Definition action_state.hpp:55
int response_timeout
Timeout for the action response.
Definition action_state.hpp:428
int maximum_retry
Maximum number of retries.
Definition action_state.hpp:430
ActionClient action_client
Shared pointer to the action client.
Definition action_state.hpp:397
typename rclcpp_action::Client< ActionT >::SharedPtr ActionClient
Shared pointer type for the action client.
Definition action_state.hpp:60
FeedbackHandler feedback_handler
Handler function for processing feedback.
Definition action_state.hpp:423
ActionState(const std::string &action_name, CreateGoalHandler create_goal_handler, ResultHandler result_handler=nullptr, FeedbackHandler feedback_handler=nullptr, int wait_timeout=-1, int response_timeout=-1, int maximum_retry=3)
Construct an ActionState with result and feedback handlers.
Definition action_state.hpp:152
std::function< void(std::shared_ptr< yasmin::blackboard::Blackboard >, std::shared_ptr< const Feedback >)> FeedbackHandler
Function type for handling feedback.
Definition action_state.hpp:70
ActionState(const std::string &action_name, CreateGoalHandler create_goal_handler, const std::set< std::string > &outcomes, int wait_timeout=-1, int response_timeout=-1, int maximum_retry=3)
Construct an ActionState with a specific action name and goal handler.
Definition action_state.hpp:94
void cancel_state()
Cancel the current action state.
Definition action_state.hpp:263
typename ActionT::Goal Goal
Alias for the action goal type.
Definition action_state.hpp:50
rclcpp_action::ResultCode action_status
Status of the action execution.
Definition action_state.hpp:411
std::function< Goal(std::shared_ptr< yasmin::blackboard::Blackboard >)> CreateGoalHandler
Function type for creating a goal.
Definition action_state.hpp:64
ActionState(const rclcpp::Node::SharedPtr &node, const std::string &action_name, CreateGoalHandler create_goal_handler, const std::set< std::string > &outcomes, ResultHandler result_handler=nullptr, FeedbackHandler feedback_handler=nullptr, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr, int wait_timeout=-1, int response_timeout=-1, int maximum_retry=3)
Construct an ActionState with a specified node and action name.
Definition action_state.hpp:217
typename rclcpp_action::Client< ActionT >::SendGoalOptions SendGoalOptions
Options for sending goals.
Definition action_state.hpp:57
std::mutex goal_handle_mutex
Mutex for protecting access to the goal handle.
Definition action_state.hpp:416
std::shared_ptr< GoalHandle > goal_handle
Handle for the current goal.
Definition action_state.hpp:414
typename ActionT::Result::SharedPtr Result
Alias for the action result type.
Definition action_state.hpp:52
CreateGoalHandler create_goal_handler
Handler function for creating goals.
Definition action_state.hpp:419
rclcpp::Node::SharedPtr node_
Shared pointer to the ROS 2 node.
Definition action_state.hpp:390
void goal_response_callback(std::shared_future< typename GoalHandle::SharedPtr > future)
Callback for handling the goal response.
Definition action_state.hpp:469
std::mutex action_done_mutex
Mutex for protecting action completion.
Definition action_state.hpp:402
std::string execute(std::shared_ptr< yasmin::blackboard::Blackboard > blackboard)
Execute the action and return the outcome.
Definition action_state.hpp:302
std::string action_name
Name of the action to communicate with.
Definition action_state.hpp:394
ResultHandler result_handler
Handler function for processing results.
Definition action_state.hpp:421
static rclcpp_action::Client< ActionT >::SharedPtr get_or_create_action_client(rclcpp::Node::SharedPtr node, const std::string &action_name, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
Get an existing action client from the cache or create a new one.
Definition ros_clients_cache.hpp:65
static std::shared_ptr< YasminNode > get_instance()
Provides access to the singleton instance of YasminNode.
Definition yasmin_node.hpp:73
#define YASMIN_LOG_INFO(text,...)
Definition logs.hpp:169
#define YASMIN_LOG_WARN(text,...)
Definition logs.hpp:164
constexpr char SUCCEED[]
Constant representing a successful action outcome.
Definition basic_outcomes.hpp:39
constexpr char CANCEL[]
Constant representing a canceled action outcome.
Definition basic_outcomes.hpp:63
constexpr char TIMEOUT[]
Constant representing a timed-out action outcome.
Definition basic_outcomes.hpp:71
constexpr char ABORT[]
Constant representing an aborted action outcome.
Definition basic_outcomes.hpp:47
Definition action_state.hpp:37