ros2_control - foxy
Loading...
Searching...
No Matches
realtime_server_goal_handle.h
1
2// Copyright (c) 2008, Willow Garage, Inc.
3//
4// Redistribution and use in source and binary forms, with or without
5// modification, are permitted provided that the following conditions are met:
6// * Redistributions of source code must retain the above copyright notice,
7// this list of conditions and the following disclaimer.
8// * Redistributions in binary form must reproduce the above copyright
9// notice, this list of conditions and the following disclaimer in the
10// documentation and/or other materials provided with the distribution.
11// * Neither the name of hiDOF, Inc. nor the names of its
12// contributors may be used to endorse or promote products derived from
13// this software without specific prior written permission.
14//
15// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25// POSSIBILITY OF SUCH DAMAGE.
27
29
30#ifndef REALTIME_TOOLS__REALTIME_SERVER_GOAL_HANDLE_H_
31#define REALTIME_TOOLS__REALTIME_SERVER_GOAL_HANDLE_H_
32
33#include <memory>
34
35#include "rclcpp/exceptions.hpp"
36#include "rclcpp/logging.hpp"
37#include "rclcpp_action/server_goal_handle.hpp"
38
39namespace realtime_tools
40{
41
42template<class Action>
44{
45private:
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
62public:
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
68 std::shared_ptr<GoalHandle> & gh,
69 const ResultSharedPtr & preallocated_result = nullptr,
70 const FeedbackSharedPtr & preallocated_feedback = nullptr)
72 gh, preallocated_result, preallocated_feedback, rclcpp::get_logger("realtime_tools"))
73 {
74 }
75
77 std::shared_ptr<GoalHandle> & gh,
78 const ResultSharedPtr & preallocated_result,
79 const FeedbackSharedPtr & preallocated_feedback,
80 rclcpp::Logger logger)
81 : req_abort_(false),
82 req_cancel_(false),
83 req_succeed_(false),
84 req_execute_(false),
85 logger_(logger),
86 gh_(gh),
87 preallocated_result_(preallocated_result),
88 preallocated_feedback_(preallocated_feedback)
89 {
90 if (!preallocated_result_) {preallocated_result_.reset(new typename Action::Result);}
91 if (!preallocated_feedback_) {preallocated_feedback_.reset(new typename Action::Feedback);}
92 }
93
94 void setAborted(ResultSharedPtr result = nullptr)
95 {
96 if (req_execute_ && !req_succeed_ && !req_abort_ && !req_cancel_) {
97 std::lock_guard<std::mutex> guard(mutex_);
98
99 req_result_ = result;
100 req_abort_ = true;
101 }
102 }
103
104 void setCanceled(ResultSharedPtr result = nullptr)
105 {
106 if (req_execute_ && !req_succeed_ && !req_abort_ && !req_cancel_) {
107 std::lock_guard<std::mutex> guard(mutex_);
108
109 req_result_ = result;
110 req_cancel_ = true;
111 }
112 }
113
114 void setSucceeded(ResultSharedPtr result = nullptr)
115 {
116 if (req_execute_ && !req_succeed_ && !req_abort_ && !req_cancel_) {
117 std::lock_guard<std::mutex> guard(mutex_);
118
119 req_result_ = result;
120 req_succeed_ = true;
121 }
122 }
123
124 void setFeedback(FeedbackSharedPtr feedback = nullptr)
125 {
126 std::lock_guard<std::mutex> guard(mutex_);
127 req_feedback_ = feedback;
128 }
129
130 void execute()
131 {
132 if (!req_succeed_ && !req_abort_ && !req_cancel_) {
133 std::lock_guard<std::mutex> guard(mutex_);
134 req_execute_ = true;
135 }
136 }
137
138 bool valid() {return nullptr != gh_.get();}
139
140 void runNonRealtime()
141 {
142 if (!valid()) {return;}
143
144 std::lock_guard<std::mutex> guard(mutex_);
145
146 try {
147 if (req_execute_ && !gh_->is_executing() && gh_->is_active() && !gh_->is_canceling()) {
148 gh_->execute();
149 }
150 if (req_abort_ && gh_->is_executing()) {
151 gh_->abort(req_result_);
152 req_abort_ = false;
153 }
154 if (req_cancel_ && gh_->is_active()) {
155 gh_->canceled(req_result_);
156 req_cancel_ = false;
157 }
158 if (req_succeed_ && !gh_->is_canceling()) {
159 gh_->succeed(req_result_);
160 req_succeed_ = false;
161 }
162 if (req_feedback_ && gh_->is_executing()) {
163 gh_->publish_feedback(req_feedback_);
164 }
165 } catch (const rclcpp::exceptions::RCLErrorBase & e) {
166 // Likely invalid state transition
167 RCLCPP_WARN(logger_, "%s", e.formatted_message.c_str());
168 }
169 }
170};
171
172} // namespace realtime_tools
173#endif // REALTIME_TOOLS__REALTIME_SERVER_GOAL_HANDLE_H_
Definition joint_trajectory_controller.hpp:50
Definition realtime_server_goal_handle.h:44
Definition realtime_box.h:39