ros2_control - rolling
Loading...
Searching...
No Matches
realtime_server_goal_handle.hpp
1// Copyright (c) 2008, Willow Garage, Inc.
2//
3// Redistribution and use in source and binary forms, with or without
4// modification, are permitted provided that the following conditions are met:
5//
6// * Redistributions of source code must retain the above copyright
7// notice, this list of conditions and the following disclaimer.
8//
9// * Redistributions in binary form must reproduce the above copyright
10// notice, this list of conditions and the following disclaimer in the
11// documentation and/or other materials provided with the distribution.
12//
13// * Neither the name of the Willow Garage, Inc. nor the names of its
14// contributors may be used to endorse or promote products derived from
15// this software without specific prior written permission.
16//
17// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27// POSSIBILITY OF SUCH DAMAGE.
28
30
31#ifndef REALTIME_TOOLS__REALTIME_SERVER_GOAL_HANDLE_HPP_
32#define REALTIME_TOOLS__REALTIME_SERVER_GOAL_HANDLE_HPP_
33
34#include <atomic>
35#include <memory>
36
37#include "rclcpp/exceptions.hpp"
38#include "rclcpp/logging.hpp"
39#include "rclcpp_action/server_goal_handle.hpp"
40
41// prio_inherit_mutex uses pthread APIs not available on Windows
42#ifndef _WIN32
43#include "realtime_tools/mutex.hpp"
44#else
45#include <mutex>
46#endif
47
48namespace realtime_tools
49{
50#ifndef _WIN32
51using rt_server_goal_handle_mutex = prio_inherit_mutex;
52#else
53using rt_server_goal_handle_mutex = std::mutex;
54#endif
55template <class Action>
57{
58private:
59 using GoalHandle = rclcpp_action::ServerGoalHandle<Action>;
60 using ResultSharedPtr = typename Action::Result::SharedPtr;
61 using FeedbackSharedPtr = typename Action::Feedback::SharedPtr;
62
63 std::atomic<bool> req_abort_;
64 std::atomic<bool> req_cancel_;
65 std::atomic<bool> req_succeed_;
66 std::atomic<bool> req_execute_;
67
69 ResultSharedPtr req_result_;
70 FeedbackSharedPtr req_feedback_;
71 rclcpp::Logger logger_;
72
73public:
74 std::shared_ptr<GoalHandle> gh_;
75 ResultSharedPtr preallocated_result_; // Preallocated so it can be used in realtime
76 FeedbackSharedPtr preallocated_feedback_; // Preallocated so it can be used in realtime
77
79 std::shared_ptr<GoalHandle> & gh, const ResultSharedPtr & preallocated_result = nullptr,
80 const FeedbackSharedPtr & preallocated_feedback = nullptr)
82 gh, preallocated_result, preallocated_feedback, rclcpp::get_logger("realtime_tools"))
83 {
84 }
85
87 std::shared_ptr<GoalHandle> & gh, const ResultSharedPtr & preallocated_result,
88 const FeedbackSharedPtr & preallocated_feedback, rclcpp::Logger logger)
89 : req_abort_(false),
90 req_cancel_(false),
91 req_succeed_(false),
92 req_execute_(false),
93 logger_(logger),
94 gh_(gh),
95 preallocated_result_(preallocated_result),
96 preallocated_feedback_(preallocated_feedback)
97 {
98 if (!preallocated_result_) {
99 preallocated_result_.reset(new typename Action::Result);
100 }
101 if (!preallocated_feedback_) {
102 preallocated_feedback_.reset(new typename Action::Feedback);
103 }
104 }
105
106 void setAborted(ResultSharedPtr result = nullptr)
107 {
108 if (
109 req_execute_.load(std::memory_order_acquire) &&
110 !req_succeed_.load(std::memory_order_acquire) &&
111 !req_abort_.load(std::memory_order_acquire) && !req_cancel_.load(std::memory_order_acquire)) {
112 std::lock_guard<rt_server_goal_handle_mutex> guard(mutex_);
113
114 req_result_ = result;
115 req_abort_.store(true, std::memory_order_release);
116 }
117 }
118
119 void setCanceled(ResultSharedPtr result = nullptr)
120 {
121 if (
122 req_execute_.load(std::memory_order_acquire) &&
123 !req_succeed_.load(std::memory_order_acquire) &&
124 !req_abort_.load(std::memory_order_acquire) && !req_cancel_.load(std::memory_order_acquire)) {
125 std::lock_guard<rt_server_goal_handle_mutex> guard(mutex_);
126
127 req_result_ = result;
128 req_cancel_.store(true, std::memory_order_release);
129 }
130 }
131
132 void setSucceeded(ResultSharedPtr result = nullptr)
133 {
134 if (
135 req_execute_.load(std::memory_order_acquire) &&
136 !req_succeed_.load(std::memory_order_acquire) &&
137 !req_abort_.load(std::memory_order_acquire) && !req_cancel_.load(std::memory_order_acquire)) {
138 std::lock_guard<rt_server_goal_handle_mutex> guard(mutex_);
139
140 req_result_ = result;
141 req_succeed_.store(true, std::memory_order_release);
142 }
143 }
144
175 bool setFeedback(FeedbackSharedPtr feedback = nullptr)
176 {
177 std::unique_lock<rt_server_goal_handle_mutex> lock(mutex_, std::try_to_lock);
178 if (lock.owns_lock()) {
179 req_feedback_ = feedback;
180 return true;
181 }
182 return false;
183 }
184
185 void execute()
186 {
187 if (
188 !req_succeed_.load(std::memory_order_acquire) &&
189 !req_abort_.load(std::memory_order_acquire) && !req_cancel_.load(std::memory_order_acquire)) {
190 std::lock_guard<rt_server_goal_handle_mutex> guard(mutex_);
191 req_execute_.store(true, std::memory_order_release);
192 }
193 }
194
195 bool valid() { return nullptr != gh_.get(); }
196
197 void runNonRealtime()
198 {
199 if (!valid()) {
200 return;
201 }
202
203 std::lock_guard<rt_server_goal_handle_mutex> guard(mutex_);
204
205 try {
206 if (
207 req_execute_.load(std::memory_order_acquire) && !gh_->is_executing() && gh_->is_active() &&
208 !gh_->is_canceling()) {
209 gh_->execute();
210 }
211 if (req_abort_.load(std::memory_order_acquire) && gh_->is_executing()) {
212 gh_->abort(req_result_);
213 req_abort_.store(false, std::memory_order_release);
214 }
215 if (req_cancel_.load(std::memory_order_acquire) && gh_->is_active()) {
216 gh_->canceled(req_result_);
217 req_cancel_.store(false, std::memory_order_release);
218 }
219 if (req_succeed_.load(std::memory_order_acquire) && !gh_->is_canceling()) {
220 gh_->succeed(req_result_);
221 req_succeed_.store(false, std::memory_order_release);
222 }
223 if (req_feedback_ && gh_->is_executing()) {
224 gh_->publish_feedback(req_feedback_);
225 }
226 } catch (const rclcpp::exceptions::RCLErrorBase & e) {
227 // Likely invalid state transition
228 RCLCPP_WARN(logger_, "%s", e.formatted_message.c_str());
229 }
230 }
231};
232
233} // namespace realtime_tools
234#endif // REALTIME_TOOLS__REALTIME_SERVER_GOAL_HANDLE_HPP_
Definition realtime_server_goal_handle.hpp:57
bool setFeedback(FeedbackSharedPtr feedback=nullptr)
Set feedback to be published by runNonRealtime().
Definition realtime_server_goal_handle.hpp:175
A class template that provides a pthread mutex with the priority inheritance protocol.
Definition mutex.hpp:78
A pthread mutex wrapper that provides a mutex with the priority inheritance protocol and a priority c...
Definition async_function_handler.hpp:40