16#ifndef YASMIN_ROS__SERVICE_STATE_HPP
17#define YASMIN_ROS__SERVICE_STATE_HPP
19#include <condition_variable>
26#include "rclcpp/rclcpp.hpp"
35using namespace std::placeholders;
50 using Request =
typename ServiceT::Request::SharedPtr;
52 using Response =
typename ServiceT::Response::SharedPtr;
56 std::function<
Request(std::shared_ptr<yasmin::blackboard::Blackboard>)>;
59 std::shared_ptr<yasmin::blackboard::Blackboard>,
Response)>;
118 const std::set<std::string> &
outcomes,
119 rclcpp::CallbackGroup::SharedPtr callback_group =
nullptr,
165 const std::set<std::string> &
outcomes,
192 const std::set<std::string> &
outcomes,
194 rclcpp::CallbackGroup::SharedPtr callback_group,
201 if (this->wait_timeout > 0 || this->response_timeout > 0) {
210 if (node ==
nullptr) {
227 throw std::invalid_argument(
"create_request_handler is needed");
243 execute(std::shared_ptr<yasmin::blackboard::Blackboard> blackboard)
override {
252 std::chrono::duration<int64_t, std::ratio<1>>(this->wait_timeout))) {
259 this->
srv_name.c_str(), retry_count,
260 this->maximum_retry);
274 if (this->response_timeout > 0) {
276 lock, std::chrono::seconds(this->response_timeout)) ==
277 std::cv_status::timeout) {
279 "Timeout reached while waiting for response from service '%s'",
284 this->
srv_name.c_str(), retry_count,
285 this->maximum_retry);
301 std::string outcome =
360 std::lock_guard<std::mutex> lock(this->response_done_mutex);
361 this->service_response = response.get();
362 this->response_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
static rclcpp::Client< ServiceT >::SharedPtr get_or_create_service_client(rclcpp::Node::SharedPtr node, const std::string &service_name, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
Get an existing service client from the cache or create a new one.
Definition ros_clients_cache.hpp:114
std::condition_variable response_done_cond
Condition variable for response completion.
Definition service_state.hpp:332
CreateRequestHandler create_request_handler
Function to create service requests.
Definition service_state.hpp:319
std::function< Request(std::shared_ptr< yasmin::blackboard::Blackboard >)> CreateRequestHandler
Function type for creating a request.
Definition service_state.hpp:55
ServiceState(const std::string &srv_name, CreateRequestHandler create_request_handler, const std::set< std::string > &outcomes, ResponseHandler response_handler, int wait_timeout=-1, int response_timeout=-1, int maximum_retry=3)
Construct a ServiceState with a request handler and response handler.
Definition service_state.hpp:163
ServiceState(const rclcpp::Node::SharedPtr &node, const std::string &srv_name, CreateRequestHandler create_request_handler, const std::set< std::string > &outcomes, ResponseHandler response_handler, rclcpp::CallbackGroup::SharedPtr callback_group, int wait_timeout=-1, int response_timeout=-1, int maximum_retry=3)
Construct a ServiceState with a ROS 2 node and handlers.
Definition service_state.hpp:190
ResponseHandler response_handler
Function to handle service responses.
Definition service_state.hpp:321
ServiceState(const std::string &srv_name, CreateRequestHandler create_request_handler, const std::set< std::string > &outcomes, int wait_timeout=-1, int response_timeout=-1, int maximum_retry=3)
Construct a ServiceState with a request handler and outcomes.
Definition service_state.hpp:94
ServiceState(const std::string &srv_name, CreateRequestHandler create_request_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 a ServiceState with a request handler and outcomes.
Definition service_state.hpp:116
typename ServiceT::Response::SharedPtr Response
Alias for the service response type.
Definition service_state.hpp:52
typename ServiceT::Request::SharedPtr Request
Alias for the service request type.
Definition service_state.hpp:50
std::mutex response_done_mutex
Mutex for protecting response completion.
Definition service_state.hpp:334
int wait_timeout
Maximum wait time for service availability.
Definition service_state.hpp:325
std::string execute(std::shared_ptr< yasmin::blackboard::Blackboard > blackboard) override
Execute the service call and handle the response.
Definition service_state.hpp:243
std::string srv_name
Name of the service.
Definition service_state.hpp:323
rclcpp::Node::SharedPtr node_
Shared pointer to the ROS 2 node.
Definition service_state.hpp:313
int response_timeout
Timeout for the service response.
Definition service_state.hpp:327
Response service_response
Shared pointer to the service response.
Definition service_state.hpp:336
std::shared_ptr< rclcpp::Client< ServiceT > > service_client
Shared pointer to the service client.
Definition service_state.hpp:317
std::function< std::string( std::shared_ptr< yasmin::blackboard::Blackboard >, Response)> ResponseHandler
Function type for handling a response.
Definition service_state.hpp:58
ServiceState(const std::string &srv_name, CreateRequestHandler create_request_handler, int wait_timeout=-1, int response_timeout=-1, int maximum_retry=3)
Construct a ServiceState with a request handler and outcomes.
Definition service_state.hpp:74
int maximum_retry
Maximum number of retries.
Definition service_state.hpp:329
ServiceState(const std::string &srv_name, CreateRequestHandler create_request_handler, ResponseHandler response_handler, int wait_timeout=-1, int response_timeout=-1, int maximum_retry=3)
Construct a ServiceState with a request handler and response handler.
Definition service_state.hpp:140
void response_callback(typename rclcpp::Client< ServiceT >::SharedFuture response)
Callback for handling the service response.
Definition service_state.hpp:359
Request create_request(std::shared_ptr< yasmin::blackboard::Blackboard > blackboard)
Create a service request based on the blackboard.
Definition service_state.hpp:346
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