31 #ifndef REALTIME_TOOLS__REALTIME_SERVER_GOAL_HANDLE_HPP_
32 #define REALTIME_TOOLS__REALTIME_SERVER_GOAL_HANDLE_HPP_
36 #include "rclcpp/exceptions.hpp"
37 #include "rclcpp/logging.hpp"
38 #include "rclcpp_action/server_goal_handle.hpp"
42 template <
class Action>
46 using GoalHandle = rclcpp_action::ServerGoalHandle<Action>;
47 using ResultSharedPtr =
typename Action::Result::SharedPtr;
48 using FeedbackSharedPtr =
typename Action::Feedback::SharedPtr;
56 ResultSharedPtr req_result_;
57 FeedbackSharedPtr req_feedback_;
58 rclcpp::Logger logger_;
61 std::shared_ptr<GoalHandle> gh_;
62 ResultSharedPtr preallocated_result_;
63 FeedbackSharedPtr preallocated_feedback_;
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"))
74 std::shared_ptr<GoalHandle> & gh,
const ResultSharedPtr & preallocated_result,
75 const FeedbackSharedPtr & preallocated_feedback, rclcpp::Logger logger)
82 preallocated_result_(preallocated_result),
83 preallocated_feedback_(preallocated_feedback)
85 if (!preallocated_result_) {
86 preallocated_result_.reset(
new typename Action::Result);
88 if (!preallocated_feedback_) {
89 preallocated_feedback_.reset(
new typename Action::Feedback);
93 void setAborted(ResultSharedPtr result =
nullptr)
95 if (req_execute_ && !req_succeed_ && !req_abort_ && !req_cancel_) {
96 std::lock_guard<std::mutex> guard(mutex_);
103 void setCanceled(ResultSharedPtr result =
nullptr)
105 if (req_execute_ && !req_succeed_ && !req_abort_ && !req_cancel_) {
106 std::lock_guard<std::mutex> guard(mutex_);
108 req_result_ = result;
113 void setSucceeded(ResultSharedPtr result =
nullptr)
115 if (req_execute_ && !req_succeed_ && !req_abort_ && !req_cancel_) {
116 std::lock_guard<std::mutex> guard(mutex_);
118 req_result_ = result;
123 void setFeedback(FeedbackSharedPtr feedback =
nullptr)
125 std::lock_guard<std::mutex> guard(mutex_);
126 req_feedback_ = feedback;
131 if (!req_succeed_ && !req_abort_ && !req_cancel_) {
132 std::lock_guard<std::mutex> guard(mutex_);
137 bool valid() {
return nullptr != gh_.get(); }
139 void runNonRealtime()
145 std::lock_guard<std::mutex> guard(mutex_);
148 if (req_execute_ && !gh_->is_executing() && gh_->is_active() && !gh_->is_canceling()) {
151 if (req_abort_ && gh_->is_executing()) {
152 gh_->abort(req_result_);
155 if (req_cancel_ && gh_->is_active()) {
156 gh_->canceled(req_result_);
159 if (req_succeed_ && !gh_->is_canceling()) {
160 gh_->succeed(req_result_);
161 req_succeed_ =
false;
163 if (req_feedback_ && gh_->is_executing()) {
164 gh_->publish_feedback(req_feedback_);
166 }
catch (
const rclcpp::exceptions::RCLErrorBase & e) {
168 RCLCPP_WARN(logger_,
"%s", e.formatted_message.c_str());