C++ YASMIN (Yet Another State MachINe)
Loading...
Searching...
No Matches
action_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__ACTION_STATE_HPP
17#define YASMIN_ROS__ACTION_STATE_HPP
18
19#include <condition_variable>
20#include <functional>
21#include <memory>
22#include <set>
23#include <string>
24
25#include "rclcpp/rclcpp.hpp"
26#include "rclcpp_action/rclcpp_action.hpp"
27
29#include "yasmin/logs.hpp"
30#include "yasmin/state.hpp"
34
35using namespace std::placeholders;
36
37namespace yasmin_ros {
38
48template <typename ActionT> class ActionState : public yasmin::State {
50 using Goal = typename ActionT::Goal;
52 using Result = typename ActionT::Result::SharedPtr;
53
55 using Feedback = typename ActionT::Feedback;
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>)>;
67 using ResultHandler = std::function<std::string(
68 std::shared_ptr<yasmin::blackboard::Blackboard>, Result)>;
71 std::function<void(std::shared_ptr<yasmin::blackboard::Blackboard>,
72 std::shared_ptr<const Feedback>)>;
73
74public:
94 ActionState(const std::string &action_name,
96 const std::set<std::string> &outcomes, int wait_timeout = -1,
97 int response_timeout = -1, int maximum_retry = 3)
99 nullptr, nullptr, nullptr, wait_timeout, response_timeout,
100 maximum_retry) {}
101
122 ActionState(const std::string &action_name,
124 const std::set<std::string> &outcomes,
125 rclcpp::CallbackGroup::SharedPtr callback_group = nullptr,
126 int wait_timeout = -1, int response_timeout = -1,
127 int maximum_retry = 3)
129 nullptr, nullptr, callback_group, wait_timeout,
131
160
192
217 ActionState(const rclcpp::Node::SharedPtr &node,
218 const std::string &action_name,
220 const std::set<std::string> &outcomes,
223 rclcpp::CallbackGroup::SharedPtr callback_group = nullptr,
224 int wait_timeout = -1, int response_timeout = -1,
225 int maximum_retry = 3)
232
233 if (this->wait_timeout > 0 || this->response_timeout > 0) {
234 this->outcomes.insert(basic_outcomes::TIMEOUT);
235 }
236
237 if (outcomes.size() > 0) {
238 for (const std::string &outcome : outcomes) {
239 this->outcomes.insert(outcome);
240 }
241 }
242
243 if (node == nullptr) {
245 } else {
246 this->node_ = node;
247 }
248
250 this->node_, action_name, callback_group);
251
252 if (this->create_goal_handler == nullptr) {
253 throw std::invalid_argument("create_goal_handler is needed");
254 }
255 }
256
264 std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
265
266 if (this->goal_handle) {
267 this->action_client->async_cancel_goal(
268 this->goal_handle, std::bind(&ActionState::cancel_done, this));
269
270 std::unique_lock<std::mutex> lock(this->action_cancel_mutex);
271 this->action_cancel_cond.wait(lock);
272 }
273
275 }
276
283 void cancel_done() { this->action_cancel_cond.notify_all(); }
284
301 std::string
302 execute(std::shared_ptr<yasmin::blackboard::Blackboard> blackboard) {
303
304 std::unique_lock<std::mutex> lock(this->action_done_mutex);
305 int retry_count = 0;
306
307 Goal goal = this->create_goal_handler(blackboard);
308
309 // Wait for the action server to be available
310 YASMIN_LOG_INFO("Waiting for action '%s'", this->action_name.c_str());
311
312 while (!this->action_client->wait_for_action_server(
313 std::chrono::duration<int64_t, std::ratio<1>>(this->wait_timeout))) {
314 YASMIN_LOG_WARN("Timeout reached, action '%s' is not available",
315 this->action_name.c_str());
316 if (retry_count < this->maximum_retry) {
317 retry_count++;
318 YASMIN_LOG_WARN("Retrying to connect to action '%s' "
319 "(%d/%d)",
320 this->action_name.c_str(), retry_count,
321 this->maximum_retry);
322 } else {
324 }
325 }
326
327 // Prepare options for sending the goal
328 SendGoalOptions send_goal_options;
329 send_goal_options.goal_response_callback =
330 std::bind(&ActionState::goal_response_callback, this, _1);
331
332 send_goal_options.result_callback =
333 std::bind(&ActionState::result_callback, this, _1);
334
335 if (this->feedback_handler) {
336 send_goal_options.feedback_callback =
337 [this, blackboard](typename GoalHandle::SharedPtr,
338 std::shared_ptr<const Feedback> feedback) {
339 this->feedback_handler(blackboard, feedback);
340 };
341 }
342
343 YASMIN_LOG_INFO("Sending goal to action '%s'", this->action_name.c_str());
344 this->action_client->async_send_goal(goal, send_goal_options);
345
346 if (this->response_timeout > 0) {
347 while (this->action_done_cond.wait_for(
348 lock, std::chrono::seconds(this->response_timeout)) ==
349 std::cv_status::timeout) {
351 "Timeout reached while waiting for response from action '%s'",
352 this->action_name.c_str());
353 if (retry_count < this->maximum_retry) {
354 retry_count++;
355 YASMIN_LOG_WARN("Retrying to wait for action '%s' response (%d/%d)",
356 this->action_name.c_str(), retry_count,
357 this->maximum_retry);
358 } else {
360 }
361 }
362 } else {
363 this->action_done_cond.wait(lock);
364 }
365
366 if (this->is_canceled()) {
368 }
369
370 switch (this->action_status) {
371 case rclcpp_action::ResultCode::CANCELED:
373
374 case rclcpp_action::ResultCode::ABORTED:
376
377 case rclcpp_action::ResultCode::SUCCEEDED:
378 if (this->result_handler) {
379 return this->result_handler(blackboard, this->action_result);
380 }
382
383 default:
385 }
386 }
387
388protected:
390 rclcpp::Node::SharedPtr node_;
391
392private:
394 std::string action_name;
395
398
400 std::condition_variable action_done_cond;
404 std::condition_variable action_cancel_cond;
407
411 rclcpp_action::ResultCode action_status;
412
414 std::shared_ptr<GoalHandle> goal_handle;
417
424
431
432#if __has_include("rclcpp/version.h")
433#include "rclcpp/version.h"
434#if RCLCPP_VERSION_GTE(2, 4, 3)
442 void
443 goal_response_callback(const typename GoalHandle::SharedPtr &goal_handle) {
444 std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
445 this->goal_handle = goal_handle;
446 }
447#else
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();
459 }
460#endif
461#else
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();
473 }
474#endif
475
483 void result_callback(const typename GoalHandle::WrappedResult &result) {
484 this->action_result = result.result;
485 this->action_status = result.code;
486 this->action_done_cond.notify_one();
487 }
488};
489
490} // namespace yasmin_ros
491
492#endif // YASMIN_ROS__ACTION_STATE_HPP
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