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