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 <string>
23
24#include "rclcpp/rclcpp.hpp"
25#include "rclcpp_action/rclcpp_action.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 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>;
67 std::function<std::string(yasmin::Blackboard::SharedPtr, Result)>;
70 std::shared_ptr<const Feedback>)>;
71
72public:
77
78
97 ActionState(const std::string &action_name,
99 const yasmin::Outcomes &outcomes, int wait_timeout = -1,
100 int response_timeout = -1, int maximum_retry = 3)
102 nullptr, nullptr, nullptr, wait_timeout, response_timeout,
103 maximum_retry) {}
104
125 ActionState(const std::string &action_name,
128 rclcpp::CallbackGroup::SharedPtr callback_group = nullptr,
129 int wait_timeout = -1, int response_timeout = -1,
130 int maximum_retry = 3)
132 nullptr, nullptr, callback_group, wait_timeout,
134
163
195
220 ActionState(const rclcpp::Node::SharedPtr &node,
221 const std::string &action_name,
226 rclcpp::CallbackGroup::SharedPtr callback_group = nullptr,
227 int wait_timeout = -1, int response_timeout = -1,
228 int maximum_retry = 3)
235
236 if (this->wait_timeout > 0 || this->response_timeout > 0) {
237 this->outcomes.insert(basic_outcomes::TIMEOUT);
238 }
239
240 if (outcomes.size() > 0) {
241 for (const std::string &outcome : outcomes) {
242 this->outcomes.insert(outcome);
243 }
244 }
245
246 if (node == nullptr) {
248 } else {
249 this->node_ = node;
250 }
251
253 this->node_, action_name, callback_group);
254
255 if (this->create_goal_handler == nullptr) {
256 throw std::invalid_argument("create_goal_handler is needed");
257 }
258 }
259
266 void cancel_state() override {
267
268 bool waiting_for_cancel = false;
269
270 {
271 std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
272
273 if (this->goal_handle) {
274 auto future_cancel = this->action_client->async_cancel_goal(
275 this->goal_handle, std::bind(&ActionState::cancel_done, this));
276 waiting_for_cancel = true;
277 }
278 }
279
280 // Wait for cancellation to complete outside of the goal_handle_mutex lock
281 if (waiting_for_cancel) {
282 std::unique_lock<std::mutex> cancel_lock(this->action_cancel_mutex);
283 this->action_cancel_cond.wait(cancel_lock);
284 }
285
286 // Wake up the execute() method if it's waiting
288 }
289
296 void cancel_done() { this->action_cancel_cond.notify_all(); }
297
314 std::string execute(yasmin::Blackboard::SharedPtr blackboard) {
315
316 std::unique_lock<std::mutex> lock(this->action_done_mutex);
317 int retry_count = 0;
318
319 Goal goal = this->create_goal_handler(blackboard);
320
321 // Wait for the action server to be available
322 YASMIN_LOG_INFO("Waiting for action '%s'", this->action_name.c_str());
323
324 while (!this->action_client->wait_for_action_server(
325 std::chrono::duration<int64_t, std::ratio<1>>(this->wait_timeout))) {
326
327 if (this->is_canceled()) {
329 }
330
331 YASMIN_LOG_WARN("Timeout reached, action '%s' is not available",
332 this->action_name.c_str());
333 if (retry_count < this->maximum_retry) {
334 retry_count++;
335 YASMIN_LOG_WARN("Retrying to connect to action '%s' "
336 "(%d/%d)",
337 this->action_name.c_str(), retry_count,
338 this->maximum_retry);
339 } else {
341 }
342 }
343
344 if (this->is_canceled()) {
346 }
347
348 // Prepare options for sending the goal
349 SendGoalOptions send_goal_options;
350 send_goal_options.goal_response_callback =
351 std::bind(&ActionState::goal_response_callback, this, _1);
352 send_goal_options.result_callback =
353 std::bind(&ActionState::result_callback, this, _1);
354
355 if (this->feedback_handler) {
356 send_goal_options.feedback_callback =
357 [this, blackboard](typename GoalHandle::SharedPtr,
358 std::shared_ptr<const Feedback> feedback) {
359 this->feedback_handler(blackboard, feedback);
360 };
361 }
362
363 // Send the goal to the action server
364 YASMIN_LOG_INFO("Sending goal to action '%s'", this->action_name.c_str());
365 this->action_client->async_send_goal(goal, send_goal_options);
366
367 if (this->response_timeout > 0) {
368 while (this->action_done_cond.wait_for(
369 lock, std::chrono::seconds(this->response_timeout)) ==
370 std::cv_status::timeout) {
371
372 if (this->is_canceled()) {
374 }
375
377 "Timeout reached while waiting for response from action '%s'",
378 this->action_name.c_str());
379 if (retry_count < this->maximum_retry) {
380 retry_count++;
381 YASMIN_LOG_WARN("Retrying to wait for action '%s' response (%d/%d)",
382 this->action_name.c_str(), retry_count,
383 this->maximum_retry);
384 } else {
386 }
387 }
388
389 } else {
390 this->action_done_cond.wait(lock);
391 }
392
393 if (this->is_canceled()) {
395 }
396
397 switch (this->action_status) {
398 case rclcpp_action::ResultCode::CANCELED:
400
401 case rclcpp_action::ResultCode::ABORTED:
403
404 case rclcpp_action::ResultCode::SUCCEEDED:
405 if (this->result_handler) {
406 return this->result_handler(blackboard, this->action_result);
407 }
409
410 default:
412 }
413 }
414
415protected:
417 rclcpp::Node::SharedPtr node_;
418
419private:
421 std::string action_name;
424
426 std::condition_variable action_done_cond;
430 std::condition_variable action_cancel_cond;
433
437 rclcpp_action::ResultCode action_status;
438
440 std::shared_ptr<GoalHandle> goal_handle;
443
450
457
458#if __has_include("rclcpp/version.h")
459#include "rclcpp/version.h"
460#if RCLCPP_VERSION_GTE(2, 4, 3) // Greater or equal to latest Foxy
468 void
469 goal_response_callback(const typename GoalHandle::SharedPtr &goal_handle) {
470 std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
471 this->goal_handle = goal_handle;
472 }
473#else
482 std::shared_future<typename GoalHandle::SharedPtr> future) {
483 std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
484 this->goal_handle = future.get();
485 }
486#endif
487#else
496 std::shared_future<typename GoalHandle::SharedPtr> future) {
497 std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
498 this->goal_handle = future.get();
499 }
500#endif
501
509 void result_callback(const typename GoalHandle::WrappedResult &result) {
510 this->action_result = result.result;
511 this->action_status = result.code;
512 this->action_done_cond.notify_one();
513 }
514};
515
516} // namespace yasmin_ros
517
518#endif // YASMIN_ROS__ACTION_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
virtual void cancel_state()
Cancels the current state execution.
Definition state.hpp:141
void result_callback(const typename GoalHandle::WrappedResult &result)
Callback for handling the result of the action.
Definition action_state.hpp:509
int wait_timeout
Maximum time to wait for the action server.
Definition action_state.hpp:452
std::condition_variable action_done_cond
Condition variable for action completion.
Definition action_state.hpp:426
std::function< void(yasmin::Blackboard::SharedPtr, std::shared_ptr< const Feedback >)> FeedbackHandler
Function type for handling feedback.
Definition action_state.hpp:69
std::mutex action_cancel_mutex
Mutex for protecting action cancellation.
Definition action_state.hpp:432
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 yasmin::Outcomes &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:125
void cancel_done()
Notify that the action cancellation has completed.
Definition action_state.hpp:296
Result action_result
Shared pointer to the action result.
Definition action_state.hpp:435
std::string execute(yasmin::Blackboard::SharedPtr blackboard)
Execute the action and return the outcome.
Definition action_state.hpp:314
void cancel_state() override
Cancel the current action state.
Definition action_state.hpp:266
std::condition_variable action_cancel_cond
Condition variable for action cancellation.
Definition action_state.hpp:430
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:454
ActionState(const std::string &action_name, CreateGoalHandler create_goal_handler, const yasmin::Outcomes &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:186
int maximum_retry
Maximum number of retries.
Definition action_state.hpp:456
ActionClient action_client
Shared pointer to the action client.
Definition action_state.hpp:423
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:449
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:155
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:437
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:442
std::function< std::string(yasmin::Blackboard::SharedPtr, Result)> ResultHandler
Function type for handling results.
Definition action_state.hpp:66
std::shared_ptr< GoalHandle > goal_handle
Handle for the current goal.
Definition action_state.hpp:440
ActionState(const rclcpp::Node::SharedPtr &node, const std::string &action_name, CreateGoalHandler create_goal_handler, const yasmin::Outcomes &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:220
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:445
rclcpp::Node::SharedPtr node_
Shared pointer to the ROS 2 node.
Definition action_state.hpp:417
void goal_response_callback(std::shared_future< typename GoalHandle::SharedPtr > future)
Callback for handling the goal response.
Definition action_state.hpp:495
std::mutex action_done_mutex
Mutex for protecting action completion.
Definition action_state.hpp:428
ActionState(const std::string &action_name, CreateGoalHandler create_goal_handler, const yasmin::Outcomes &outcomes, int wait_timeout=-1, int response_timeout=-1, int maximum_retry=3)
Shared pointer type for ActionState.
Definition action_state.hpp:97
std::string action_name
Name of the action to communicate with.
Definition action_state.hpp:421
std::function< Goal(yasmin::Blackboard::SharedPtr)> CreateGoalHandler
Function type for creating a goal.
Definition action_state.hpp:64
ResultHandler result_handler
Handler function for processing results.
Definition action_state.hpp:447
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 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
Definition blackboard.hpp:31
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