C++ YASMIN (Yet Another State MachINe)
Loading...
Searching...
No Matches
service_state.hpp
Go to the documentation of this file.
1// Copyright (C) 2023 Miguel Ángel González Santamarta
2//
3// This program is free software: you can redistribute it and/or modify
4// it under the terms of the GNU General Public License as published by
5// the Free Software Foundation, either version 3 of the License, or
6// (at your option) any later version.
7//
8// This program is distributed in the hope that it will be useful,
9// but WITHOUT ANY WARRANTY; without even the implied warranty of
10// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11// GNU General Public License for more details.
12//
13// You should have received a copy of the GNU General Public License
14// along with this program. If not, see <https://www.gnu.org/licenses/>.
15
16#ifndef YASMIN_ROS__SERVICE_STATE_HPP_
17#define YASMIN_ROS__SERVICE_STATE_HPP_
18
19#include <condition_variable>
20#include <functional>
21#include <memory>
22#include <mutex>
23#include <string>
24
25#include "rclcpp/rclcpp.hpp"
26
27#include "yasmin/blackboard.hpp"
28#include "yasmin/logs.hpp"
29#include "yasmin/state.hpp"
30#include "yasmin/types.hpp"
34
35using namespace std::placeholders;
36
37namespace yasmin_ros {
38
48template <typename ServiceT> class ServiceState : public yasmin::State {
50 using Request = typename ServiceT::Request::SharedPtr;
52 using Response = typename ServiceT::Response::SharedPtr;
53
59 std::function<std::string(yasmin::Blackboard::SharedPtr, Response)>;
60
61public:
66
67
85
105
120 ServiceState(const std::string &srv_name,
123 rclcpp::CallbackGroup::SharedPtr callback_group = nullptr,
124 int wait_timeout = -1, int response_timeout = -1,
125 int maximum_retry = 3)
127 nullptr, callback_group, wait_timeout, response_timeout,
128 maximum_retry) {}
129
151
175
194 ServiceState(const rclcpp::Node::SharedPtr &node, const std::string &srv_name,
198 rclcpp::CallbackGroup::SharedPtr callback_group,
199 int wait_timeout = -1, int response_timeout = -1,
200 int maximum_retry = 3)
204
205 if (this->wait_timeout > 0 || this->response_timeout > 0) {
206 this->outcomes.insert(basic_outcomes::TIMEOUT);
207 }
208
209 if (!outcomes.empty()) {
210 this->outcomes.insert(outcomes.begin(), outcomes.end());
211 }
212
213 // Assign the appropriate ROS 2 node
214 if (node == nullptr) {
216 } else {
217 this->node_ = node;
218 }
219
220 // Create a service client (compatible with different rclcpp versions)
221 this->service_client =
223 this->node_, srv_name, callback_group);
224
225 // Set the request and response handlers
228
229 // Validate request handler
230 if (this->create_request_handler == nullptr) {
231 throw std::invalid_argument("create_request_handler is needed");
232 }
233 }
234
246 std::string execute(yasmin::Blackboard::SharedPtr blackboard) override {
247 Request request = this->create_request(blackboard);
248 std::unique_lock<std::mutex> lock(this->response_done_mutex);
249 int retry_count = 0;
250
251 // Wait for the service to become available
252 YASMIN_LOG_INFO("Waiting for service '%s'", this->srv_name.c_str());
253
254 while (!this->service_client->wait_for_service(
255 std::chrono::duration<int64_t, std::ratio<1>>(this->wait_timeout))) {
256 YASMIN_LOG_WARN("Timeout reached, service '%s' is not available",
257 this->srv_name.c_str());
258 if (retry_count < this->maximum_retry) {
259 retry_count++;
260 YASMIN_LOG_WARN("Retrying to connect to service '%s' "
261 "(%d/%d)",
262 this->srv_name.c_str(), retry_count,
263 this->maximum_retry);
264 } else {
266 }
267 }
268
269 // Send the service request
270 YASMIN_LOG_INFO("Sending request to service '%s'", this->srv_name.c_str());
271
272 // Send request with callback
273 this->service_client->async_send_request(
274 request, std::bind(&ServiceState::response_callback, this, _1));
275
276 // Wait for response with timeout
277 if (this->response_timeout > 0) {
278 while (this->response_done_cond.wait_for(
279 lock, std::chrono::seconds(this->response_timeout)) ==
280 std::cv_status::timeout) {
282 "Timeout reached while waiting for response from service '%s'",
283 this->srv_name.c_str());
284 if (retry_count < this->maximum_retry) {
285 retry_count++;
286 YASMIN_LOG_WARN("Retrying to wait for service '%s' response (%d/%d)",
287 this->srv_name.c_str(), retry_count,
288 this->maximum_retry);
289 } else {
291 }
292 }
293 } else {
294 this->response_done_cond.wait(lock);
295 }
296
297 if (this->is_canceled()) {
299 }
300
301 // Process the service response
302 if (this->service_response) {
303 if (response_handler != nullptr) {
304 std::string outcome =
305 this->response_handler(blackboard, this->service_response);
306 return outcome;
307 }
309 } else {
311 }
312 }
313
314protected:
316 rclcpp::Node::SharedPtr node_;
317
318private:
320 std::shared_ptr<rclcpp::Client<ServiceT>> service_client;
326 std::string srv_name;
333
335 std::condition_variable response_done_cond;
340
349 return this->create_request_handler(blackboard);
350 }
351
360 void
361 response_callback(typename rclcpp::Client<ServiceT>::SharedFuture response) {
362 std::lock_guard<std::mutex> lock(this->response_done_mutex);
363 this->service_response = response.get();
364 this->response_done_cond.notify_one();
365 }
366};
367
368} // namespace yasmin_ros
369
370#endif // YASMIN_ROS__SERVICE_STATE_HPP_
std::shared_ptr< Blackboard > SharedPtr
Shared pointer type for Blackboard.
Definition blackboard.hpp:85
Represents a state in a state machine.
Definition state.hpp:46
Outcomes outcomes
The possible outcomes of this state.
Definition state.hpp:50
State(const Outcomes &outcomes)
Shared pointer type for State.
Definition state.cpp:32
bool is_canceled() const noexcept
Checks if the state has been canceled.
Definition state.cpp:52
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:335
CreateRequestHandler create_request_handler
Function to create service requests.
Definition service_state.hpp:322
std::function< Request(yasmin::Blackboard::SharedPtr)> CreateRequestHandler
Function type for creating a request.
Definition service_state.hpp:55
Request create_request(yasmin::Blackboard::SharedPtr blackboard)
Create a service request based on the blackboard.
Definition service_state.hpp:348
ResponseHandler response_handler
Function to handle service responses.
Definition service_state.hpp:324
ServiceState(const std::string &srv_name, CreateRequestHandler create_request_handler, const yasmin::Outcomes &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:120
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:337
int wait_timeout
Maximum wait time for service availability.
Definition service_state.hpp:328
std::function< std::string(yasmin::Blackboard::SharedPtr, Response)> ResponseHandler
Function type for handling a response.
Definition service_state.hpp:58
std::string srv_name
Name of the service.
Definition service_state.hpp:326
rclcpp::Node::SharedPtr node_
Shared pointer to the ROS 2 node.
Definition service_state.hpp:316
std::string execute(yasmin::Blackboard::SharedPtr blackboard) override
Execute the service call and handle the response.
Definition service_state.hpp:246
int response_timeout
Timeout for the service response.
Definition service_state.hpp:330
Response service_response
Shared pointer to the service response.
Definition service_state.hpp:339
std::shared_ptr< rclcpp::Client< ServiceT > > service_client
Shared pointer to the service client.
Definition service_state.hpp:320
ServiceState(const std::string &srv_name, CreateRequestHandler create_request_handler, const yasmin::Outcomes &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:98
ServiceState(const rclcpp::Node::SharedPtr &node, const std::string &srv_name, CreateRequestHandler create_request_handler, const yasmin::Outcomes &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:194
ServiceState(const std::string &srv_name, CreateRequestHandler create_request_handler, int wait_timeout=-1, int response_timeout=-1, int maximum_retry=3)
Shared pointer type for ServiceState.
Definition service_state.hpp:79
int maximum_retry
Maximum number of retries.
Definition service_state.hpp:332
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:144
void response_callback(typename rclcpp::Client< ServiceT >::SharedFuture response)
Callback for handling the service response.
Definition service_state.hpp:361
ServiceState(const std::string &srv_name, CreateRequestHandler create_request_handler, const yasmin::Outcomes &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:167
static YasminNode::SharedPtr get_instance()
Provides access to the singleton instance of YasminNode.
Definition yasmin_node.hpp:74
#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
StringSet Outcomes
Set of possible outcomes for states.
Definition types.hpp:77
#define YASMIN_PTR_ALIASES(ClassName)
Macro to define all pointer aliases for a class.
Definition types.hpp:52