59 using GoalHandle = rclcpp_action::ServerGoalHandle<Action>;
60 using ResultSharedPtr =
typename Action::Result::SharedPtr;
61 using FeedbackSharedPtr =
typename Action::Feedback::SharedPtr;
63 std::atomic<bool> req_abort_;
64 std::atomic<bool> req_cancel_;
65 std::atomic<bool> req_succeed_;
66 std::atomic<bool> req_execute_;
69 ResultSharedPtr req_result_;
70 FeedbackSharedPtr req_feedback_;
71 rclcpp::Logger logger_;
74 std::shared_ptr<GoalHandle> gh_;
75 ResultSharedPtr preallocated_result_;
76 FeedbackSharedPtr preallocated_feedback_;
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"))
87 std::shared_ptr<GoalHandle> & gh,
const ResultSharedPtr & preallocated_result,
88 const FeedbackSharedPtr & preallocated_feedback, rclcpp::Logger logger)
95 preallocated_result_(preallocated_result),
96 preallocated_feedback_(preallocated_feedback)
98 if (!preallocated_result_) {
99 preallocated_result_.reset(
new typename Action::Result);
101 if (!preallocated_feedback_) {
102 preallocated_feedback_.reset(
new typename Action::Feedback);
106 void setAborted(ResultSharedPtr result =
nullptr)
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_);
114 req_result_ = result;
115 req_abort_.store(
true, std::memory_order_release);
119 void setCanceled(ResultSharedPtr result =
nullptr)
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_);
127 req_result_ = result;
128 req_cancel_.store(
true, std::memory_order_release);
132 void setSucceeded(ResultSharedPtr result =
nullptr)
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_);
140 req_result_ = result;
141 req_succeed_.store(
true, std::memory_order_release);
177 std::unique_lock<rt_server_goal_handle_mutex> lock(mutex_, std::try_to_lock);
178 if (lock.owns_lock()) {
179 req_feedback_ = feedback;
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);
195 bool valid() {
return nullptr != gh_.get(); }
197 void runNonRealtime()
203 std::lock_guard<rt_server_goal_handle_mutex> guard(mutex_);
207 req_execute_.load(std::memory_order_acquire) && !gh_->is_executing() && gh_->is_active() &&
208 !gh_->is_canceling()) {
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);
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);
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);
223 if (req_feedback_ && gh_->is_executing()) {
224 gh_->publish_feedback(req_feedback_);
226 }
catch (
const rclcpp::exceptions::RCLErrorBase & e) {
228 RCLCPP_WARN(logger_,
"%s", e.formatted_message.c_str());