ros2_control - iron
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 <memory>
35
36#include "rclcpp/exceptions.hpp"
37#include "rclcpp/logging.hpp"
38#include "rclcpp_action/server_goal_handle.hpp"
39
40namespace realtime_tools
41{
42template <class Action>
44{
45private:
46 using GoalHandle = rclcpp_action::ServerGoalHandle<Action>;
47 using ResultSharedPtr = typename Action::Result::SharedPtr;
48 using FeedbackSharedPtr = typename Action::Feedback::SharedPtr;
49
50 bool req_abort_;
51 bool req_cancel_;
52 bool req_succeed_;
53 bool req_execute_;
54
55 std::mutex mutex_;
56 ResultSharedPtr req_result_;
57 FeedbackSharedPtr req_feedback_;
58 rclcpp::Logger logger_;
59
60public:
61 std::shared_ptr<GoalHandle> gh_;
62 ResultSharedPtr preallocated_result_; // Preallocated so it can be used in realtime
63 FeedbackSharedPtr preallocated_feedback_; // Preallocated so it can be used in realtime
64
66 std::shared_ptr<GoalHandle> & gh, const ResultSharedPtr & preallocated_result = nullptr,
67 const FeedbackSharedPtr & preallocated_feedback = nullptr)
69 gh, preallocated_result, preallocated_feedback, rclcpp::get_logger("realtime_tools"))
70 {
71 }
72
74 std::shared_ptr<GoalHandle> & gh, const ResultSharedPtr & preallocated_result,
75 const FeedbackSharedPtr & preallocated_feedback, rclcpp::Logger logger)
76 : req_abort_(false),
77 req_cancel_(false),
78 req_succeed_(false),
79 req_execute_(false),
80 logger_(logger),
81 gh_(gh),
82 preallocated_result_(preallocated_result),
83 preallocated_feedback_(preallocated_feedback)
84 {
85 if (!preallocated_result_) {
86 preallocated_result_.reset(new typename Action::Result);
87 }
88 if (!preallocated_feedback_) {
89 preallocated_feedback_.reset(new typename Action::Feedback);
90 }
91 }
92
93 void setAborted(ResultSharedPtr result = nullptr)
94 {
95 if (req_execute_ && !req_succeed_ && !req_abort_ && !req_cancel_) {
96 std::lock_guard<std::mutex> guard(mutex_);
97
98 req_result_ = result;
99 req_abort_ = true;
100 }
101 }
102
103 void setCanceled(ResultSharedPtr result = nullptr)
104 {
105 if (req_execute_ && !req_succeed_ && !req_abort_ && !req_cancel_) {
106 std::lock_guard<std::mutex> guard(mutex_);
107
108 req_result_ = result;
109 req_cancel_ = true;
110 }
111 }
112
113 void setSucceeded(ResultSharedPtr result = nullptr)
114 {
115 if (req_execute_ && !req_succeed_ && !req_abort_ && !req_cancel_) {
116 std::lock_guard<std::mutex> guard(mutex_);
117
118 req_result_ = result;
119 req_succeed_ = true;
120 }
121 }
122
123 void setFeedback(FeedbackSharedPtr feedback = nullptr)
124 {
125 std::lock_guard<std::mutex> guard(mutex_);
126 req_feedback_ = feedback;
127 }
128
129 void execute()
130 {
131 if (!req_succeed_ && !req_abort_ && !req_cancel_) {
132 std::lock_guard<std::mutex> guard(mutex_);
133 req_execute_ = true;
134 }
135 }
136
137 bool valid() { return nullptr != gh_.get(); }
138
139 void runNonRealtime()
140 {
141 if (!valid()) {
142 return;
143 }
144
145 std::lock_guard<std::mutex> guard(mutex_);
146
147 try {
148 if (req_execute_ && !gh_->is_executing() && gh_->is_active() && !gh_->is_canceling()) {
149 gh_->execute();
150 }
151 if (req_abort_ && gh_->is_executing()) {
152 gh_->abort(req_result_);
153 req_abort_ = false;
154 }
155 if (req_cancel_ && gh_->is_active()) {
156 gh_->canceled(req_result_);
157 req_cancel_ = false;
158 }
159 if (req_succeed_ && !gh_->is_canceling()) {
160 gh_->succeed(req_result_);
161 req_succeed_ = false;
162 }
163 if (req_feedback_ && gh_->is_executing()) {
164 gh_->publish_feedback(req_feedback_);
165 }
166 } catch (const rclcpp::exceptions::RCLErrorBase & e) {
167 // Likely invalid state transition
168 RCLCPP_WARN(logger_, "%s", e.formatted_message.c_str());
169 }
170 }
171};
172
173} // namespace realtime_tools
174#endif // REALTIME_TOOLS__REALTIME_SERVER_GOAL_HANDLE_HPP_
Definition realtime_server_goal_handle.hpp:44
A pthread mutex wrapper that provides a mutex with the priority inheritance protocol and a priority c...
Definition async_function_handler.hpp:38