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/state.hpp"
32
33using namespace std::placeholders;
34
35namespace yasmin_ros {
36
46template <typename ActionT> class ActionState : public yasmin::State {
48 using Goal = typename ActionT::Goal;
50 using Result = typename ActionT::Result::SharedPtr;
51
53 using Feedback = typename ActionT::Feedback;
56 typename rclcpp_action::Client<ActionT>::SendGoalOptions;
58 using ActionClient = typename rclcpp_action::Client<ActionT>::SharedPtr;
60 using GoalHandle = rclcpp_action::ClientGoalHandle<ActionT>;
63 std::function<Goal(std::shared_ptr<yasmin::blackboard::Blackboard>)>;
65 using ResultHandler = std::function<std::string(
66 std::shared_ptr<yasmin::blackboard::Blackboard>, Result)>;
69 std::function<void(std::shared_ptr<yasmin::blackboard::Blackboard>,
70 std::shared_ptr<const Feedback>)>;
71
72public:
89 std::set<std::string> outcomes, int timeout = -1.0)
91 nullptr, timeout) {}
92
114
139
159 ActionState(const rclcpp::Node::SharedPtr &node, std::string action_name,
161 std::set<std::string> outcomes,
163 FeedbackHandler feedback_handler = nullptr, int timeout = -1.0)
168
171
172 if (outcomes.size() > 0) {
173 for (std::string outcome : outcomes) {
174 this->outcomes.insert(outcome);
175 }
176 }
177
178 if (node == nullptr) {
180 } else {
181 this->node_ = node;
182 }
183
184 this->action_client =
185 rclcpp_action::create_client<ActionT>(this->node_, action_name);
186
187 if (this->create_goal_handler == nullptr) {
188 throw std::invalid_argument("create_goal_handler is needed");
189 }
190 }
191
199 std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
200
201 if (this->goal_handle) {
202 this->action_client->async_cancel_goal(
203 this->goal_handle, std::bind(&ActionState::cancel_done, this));
204
205 std::unique_lock<std::mutex> lock(this->action_cancel_mutex);
206 this->action_cancel_cond.wait(lock);
207 }
208
210 }
211
218 void cancel_done() { this->action_cancel_cond.notify_all(); }
219
236 std::string
237 execute(std::shared_ptr<yasmin::blackboard::Blackboard> blackboard) {
238
239 std::unique_lock<std::mutex> lock(this->action_done_mutex);
240
241 Goal goal = this->create_goal_handler(blackboard);
242
243 // Wait for the action server to be available
244 RCLCPP_INFO(this->node_->get_logger(), "Waiting for action '%s'",
245 this->action_name.c_str());
246 bool act_available = this->action_client->wait_for_action_server(
247 std::chrono::duration<int64_t, std::ratio<1>>(this->timeout));
248
249 if (!act_available) {
250 RCLCPP_WARN(this->node_->get_logger(),
251 "Timeout reached, action '%s' is not available",
252 this->action_name.c_str());
254 }
255
256 // Prepare options for sending the goal
257 SendGoalOptions send_goal_options;
258 send_goal_options.goal_response_callback =
259 std::bind(&ActionState::goal_response_callback, this, _1);
260
261 send_goal_options.result_callback =
262 std::bind(&ActionState::result_callback, this, _1);
263
264 if (this->feedback_handler) {
265 send_goal_options.feedback_callback =
266 [this, blackboard](typename GoalHandle::SharedPtr,
267 std::shared_ptr<const Feedback> feedback) {
268 this->feedback_handler(blackboard, feedback);
269 };
270 }
271
272 RCLCPP_INFO(this->node_->get_logger(), "Sending goal to action '%s'",
273 this->action_name.c_str());
274 this->action_client->async_send_goal(goal, send_goal_options);
275
276 // Wait for the action to complete
277 this->action_done_cond.wait(lock);
278
279 switch (this->action_status) {
280 case rclcpp_action::ResultCode::CANCELED:
282
283 case rclcpp_action::ResultCode::ABORTED:
285
286 case rclcpp_action::ResultCode::SUCCEEDED:
287 if (this->result_handler) {
288 return this->result_handler(blackboard, this->action_result);
289 }
291
292 default:
294 }
295 }
296
297private:
299 rclcpp::Node::SharedPtr node_;
300
302 std::string action_name;
303
307 std::condition_variable action_done_cond;
308
312 std::condition_variable action_cancel_cond;
315
319 rclcpp_action::ResultCode action_status;
320
322 std::shared_ptr<GoalHandle> goal_handle;
325
332
335
336#if defined(FOXY)
345 std::shared_future<typename GoalHandle::SharedPtr> future) {
346 std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
347 this->goal_handle = future.get();
348 }
349#else
357 void
358 goal_response_callback(const typename GoalHandle::SharedPtr &goal_handle) {
359 std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
360 this->goal_handle = goal_handle;
361 }
362#endif
363
371 void result_callback(const typename GoalHandle::WrappedResult &result) {
372 this->action_result = result.result;
373 this->action_status = result.code;
374 this->action_done_cond.notify_one();
375 }
376};
377
378} // namespace yasmin_ros
379
380#endif // YASMIN_ROS__ACTION_STATE_HPP
Represents a state in a state machine.
Definition state.hpp:42
std::set< std::string > outcomes
The possible outcomes of this state.
Definition state.hpp:46
State(std::set< std::string > outcomes)
Constructs a State with a set of possible outcomes.
Definition state.cpp:27
virtual void cancel_state()
Cancels the current state execution.
Definition state.hpp:94
A state class for handling ROS 2 action client operations.
Definition action_state.hpp:46
int timeout
Maximum time to wait for the action server.
Definition action_state.hpp:334
void result_callback(const typename GoalHandle::WrappedResult &result)
Callback for handling the result of the action.
Definition action_state.hpp:371
std::condition_variable action_done_cond
Condition variable for action completion.
Definition action_state.hpp:307
void goal_response_callback(const typename GoalHandle::SharedPtr &goal_handle)
Callback for handling the goal response.
Definition action_state.hpp:358
std::mutex action_cancel_mutex
Mutex for protecting action cancellation.
Definition action_state.hpp:314
ActionState(std::string action_name, CreateGoalHandler create_goal_handler, std::set< std::string > outcomes, ResultHandler result_handler=nullptr, FeedbackHandler feedback_handler=nullptr, int timeout=-1.0)
Construct an ActionState with outcomes and handlers.
Definition action_state.hpp:133
rclcpp_action::ClientGoalHandle< ActionT > GoalHandle
Handle for the action goal.
Definition action_state.hpp:60
std::function< std::string( std::shared_ptr< yasmin::blackboard::Blackboard >, Result)> ResultHandler
Function type for handling results.
Definition action_state.hpp:65
void cancel_done()
Notify that the action cancellation has completed.
Definition action_state.hpp:218
Result action_result
Shared pointer to the action result.
Definition action_state.hpp:317
std::condition_variable action_cancel_cond
Condition variable for action cancellation.
Definition action_state.hpp:312
typename ActionT::Feedback Feedback
Alias for the action feedback type.
Definition action_state.hpp:53
ActionClient action_client
Shared pointer to the action client.
Definition action_state.hpp:305
typename rclcpp_action::Client< ActionT >::SharedPtr ActionClient
Shared pointer type for the action client.
Definition action_state.hpp:58
FeedbackHandler feedback_handler
Handler function for processing feedback.
Definition action_state.hpp:331
std::function< void(std::shared_ptr< yasmin::blackboard::Blackboard >, std::shared_ptr< const Feedback >)> FeedbackHandler
Function type for handling feedback.
Definition action_state.hpp:68
void cancel_state()
Cancel the current action state.
Definition action_state.hpp:198
typename ActionT::Goal Goal
Alias for the action goal type.
Definition action_state.hpp:48
rclcpp_action::ResultCode action_status
Status of the action execution.
Definition action_state.hpp:319
ActionState(std::string action_name, CreateGoalHandler create_goal_handler, std::set< std::string > outcomes, int timeout=-1.0)
Construct an ActionState with a specific action name and goal handler.
Definition action_state.hpp:88
std::function< Goal(std::shared_ptr< yasmin::blackboard::Blackboard >)> CreateGoalHandler
Function type for creating a goal.
Definition action_state.hpp:62
ActionState(std::string action_name, CreateGoalHandler create_goal_handler, ResultHandler result_handler=nullptr, FeedbackHandler feedback_handler=nullptr, int timeout=-1.0)
Construct an ActionState with result and feedback handlers.
Definition action_state.hpp:109
typename rclcpp_action::Client< ActionT >::SendGoalOptions SendGoalOptions
Options for sending goals.
Definition action_state.hpp:55
std::mutex goal_handle_mutex
Mutex for protecting access to the goal handle.
Definition action_state.hpp:324
std::shared_ptr< GoalHandle > goal_handle
Handle for the current goal.
Definition action_state.hpp:322
typename ActionT::Result::SharedPtr Result
Alias for the action result type.
Definition action_state.hpp:50
CreateGoalHandler create_goal_handler
Handler function for creating goals.
Definition action_state.hpp:327
rclcpp::Node::SharedPtr node_
Shared pointer to the ROS 2 node.
Definition action_state.hpp:299
std::mutex action_done_mutex
Mutex for protecting action completion.
Definition action_state.hpp:310
std::string execute(std::shared_ptr< yasmin::blackboard::Blackboard > blackboard)
Execute the action and return the outcome.
Definition action_state.hpp:237
std::string action_name
Name of the action to communicate with.
Definition action_state.hpp:302
ResultHandler result_handler
Handler function for processing results.
Definition action_state.hpp:329
ActionState(const rclcpp::Node::SharedPtr &node, std::string action_name, CreateGoalHandler create_goal_handler, std::set< std::string > outcomes, ResultHandler result_handler=nullptr, FeedbackHandler feedback_handler=nullptr, int timeout=-1.0)
Construct an ActionState with a specified node and action name.
Definition action_state.hpp:159
static std::shared_ptr< YasminNode > get_instance()
Provides access to the singleton instance of YasminNode.
Definition yasmin_node.hpp:73
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:55
constexpr char TIMEOUT[]
Constant representing a timed-out action outcome.
Definition basic_outcomes.hpp:63
constexpr char ABORT[]
Constant representing an aborted action outcome.
Definition basic_outcomes.hpp:47
Definition action_state.hpp:35