SMACC2
Loading...
Searching...
No Matches
cp_action_client.hpp
Go to the documentation of this file.
1// Copyright 2024 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#pragma once
16
17#include <smacc2/component.hpp>
21
22#include <chrono>
23#include <functional>
24#include <future>
25#include <mutex>
26#include <optional>
27#include <rclcpp_action/rclcpp_action.hpp>
28
29namespace smacc2
30{
31namespace client_core_components
32{
33using namespace smacc2::default_events;
34
35template <typename ActionType>
37{
38public:
39 // Type aliases
40 using ActionClient = rclcpp_action::Client<ActionType>;
41 using Goal = typename ActionType::Goal;
42 using Feedback = typename ActionType::Feedback;
43 using Result = typename ActionType::Result;
44 using GoalHandle = rclcpp_action::ClientGoalHandle<ActionType>;
45 using WrappedResult = typename GoalHandle::WrappedResult;
46 using SendGoalOptions = typename ActionClient::SendGoalOptions;
48 std::function<void(std::shared_future<typename GoalHandle::SharedPtr>)>;
49 using FeedbackCallback = typename GoalHandle::FeedbackCallback;
50 using ResultCallback = typename GoalHandle::ResultCallback;
51
52 // Configuration options
53 std::optional<std::string> actionServerName;
54 std::optional<std::chrono::milliseconds> serverTimeout;
55
56 // SMACC2 Signals for component communication
63
64 // Event posting functions (set during orthogonal allocation)
65 std::function<void(const WrappedResult &)> postSuccessEvent;
66 std::function<void(const WrappedResult &)> postAbortedEvent;
67 std::function<void(const WrappedResult &)> postCancelledEvent;
68 std::function<void(const Feedback &)> postFeedbackEvent;
69
70 // Constructor
71 CpActionClient() = default;
72
74
75 virtual ~CpActionClient() = default;
76
77 // Public API
78 std::shared_future<typename GoalHandle::SharedPtr> sendGoal(
79 Goal & goal, typename smacc2::SmaccSignal<void(const WrappedResult &)>::WeakPtr resultCallback =
80 typename smacc2::SmaccSignal<void(const WrappedResult &)>::WeakPtr())
81 {
82 std::lock_guard<std::mutex> lock(actionMutex_);
83
84 SendGoalOptions options;
85
86 // Set up feedback callback
87 options.feedback_callback = feedbackCallback_;
88
89 // Set up result callback
90 options.result_callback = [this, resultCallback](const WrappedResult & result)
91 {
92 std::lock_guard<std::mutex> lock(actionMutex_);
93
94 RCLCPP_INFO_STREAM(
95 getLogger(), "[" << this->getName() << "] Action result callback, goal id: "
96 << rclcpp_action::to_string(result.goal_id));
97
98 auto resultCallbackPtr = resultCallback.lock();
99 if (resultCallbackPtr != nullptr)
100 {
101 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] Calling user result callback");
102 (*resultCallbackPtr)(result);
103 }
104 else
105 {
106 RCLCPP_INFO_STREAM(
107 getLogger(), "[" << this->getName() << "] Using default result handling");
108 this->onResult(result);
109 }
110 };
111
112 RCLCPP_INFO_STREAM(
113 getLogger(),
114 "[" << this->getName() << "] Sending goal to action server: " << (long)client_.get());
115
116 auto goalFuture = client_->async_send_goal(goal, options);
117 lastRequest_ = goalFuture;
118
119 return goalFuture;
120 }
121
123 {
124 std::lock_guard<std::mutex> lock(actionMutex_);
125
126 if (lastRequest_ && lastRequest_->valid())
127 {
128 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] Cancelling current goal");
129
130 auto cancelFuture = client_->async_cancel_all_goals();
131 lastCancelResponse_ = cancelFuture;
132 return true;
133 }
134 else
135 {
136 RCLCPP_WARN_STREAM(getLogger(), "[" << this->getName() << "] No active goal to cancel");
137 return false;
138 }
139 }
140
141 bool isServerReady() const { return client_ && client_->action_server_is_ready(); }
142
144 {
145 if (client_)
146 {
147 RCLCPP_INFO_STREAM(
148 getLogger(),
149 "[" << this->getName() << "] Waiting for action server: " << *actionServerName);
150 client_->wait_for_action_server();
151 }
152 }
153
154 // Component lifecycle
155 void onInitialize() override
156 {
157 if (!actionServerName)
158 {
159 RCLCPP_ERROR_STREAM(getLogger(), "[" << this->getName() << "] Action server name not set!");
160 return;
161 }
162
163 RCLCPP_INFO_STREAM(
164 getLogger(),
165 "[" << this->getName() << "] Initializing action client for: " << *actionServerName);
166
167 client_ = rclcpp_action::create_client<ActionType>(getNode(), *actionServerName);
168 RCLCPP_INFO_STREAM(
169 getLogger(),
170 "[" << this->getName() << "] DONE Initializing action client for: " << *actionServerName);
171
172 // Set up feedback callback
173 feedbackCallback_ = [this](auto goalHandle, auto feedback)
174 { this->onFeedback(goalHandle, feedback); };
175 }
176
177 template <typename TOrthogonal, typename TSourceObject>
179 {
180 // Set up event posting functions with proper template parameters
181 postSuccessEvent = [this](const WrappedResult & result)
183
184 postAbortedEvent = [this](const WrappedResult & result)
186
187 postCancelledEvent = [this](const WrappedResult & result)
189
190 postFeedbackEvent = [this](const Feedback & feedback)
191 {
192 auto actionFeedbackEvent = new EvActionFeedback<Feedback, TOrthogonal>();
193 // actionFeedbackEvent->client = this->owner_;
194 actionFeedbackEvent->feedbackMessage = feedback;
195 this->postEvent(actionFeedbackEvent);
196 RCLCPP_DEBUG(getLogger(), "[%s] FEEDBACK EVENT", this->getName().c_str());
197 };
198 }
199
200 // Signal connection methods
201 template <typename T>
202 boost::signals2::connection onSucceeded(void (T::*callback)(const WrappedResult &), T * object)
203 {
204 return this->getStateMachine()->createSignalConnection(onActionSucceeded_, callback, object);
205 }
206
207 template <typename T>
208 boost::signals2::connection onAborted(void (T::*callback)(const WrappedResult &), T * object)
209 {
210 return this->getStateMachine()->createSignalConnection(onActionAborted_, callback, object);
211 }
212
213 template <typename T>
214 boost::signals2::connection onCancelled(void (T::*callback)(const WrappedResult &), T * object)
215 {
216 return this->getStateMachine()->createSignalConnection(onActionCancelled_, callback, object);
217 }
218
219 template <typename T>
220 boost::signals2::connection onFeedback(void (T::*callback)(const Feedback &), T * object)
221 {
222 return this->getStateMachine()->createSignalConnection(onActionFeedback_, callback, object);
223 }
224
225 // Access to underlying client for advanced usage
226 std::shared_ptr<ActionClient> getActionClient() const { return client_; }
227
228private:
229 std::shared_ptr<ActionClient> client_ = nullptr;
230 std::optional<std::shared_future<typename GoalHandle::SharedPtr>> lastRequest_;
231 std::optional<
232 std::shared_future<typename rclcpp_action::Client<ActionType>::CancelResponse::SharedPtr>>
235 std::mutex actionMutex_;
236
238 typename GoalHandle::SharedPtr /* goalHandle */,
239 const std::shared_ptr<const Feedback> feedback_msg)
240 {
241 onActionFeedback_(*feedback_msg);
242 postFeedbackEvent(*feedback_msg);
243 }
244
245 void onResult(const WrappedResult & result_msg)
246 {
247 const auto & resultType = result_msg.code;
248
249 RCLCPP_INFO_STREAM(
250 getLogger(), "[" << this->getName() << "] Action result ["
251 << rclcpp_action::to_string(result_msg.goal_id) << "]: " << (int)resultType);
252
253 if (resultType == rclcpp_action::ResultCode::SUCCEEDED)
254 {
255 RCLCPP_INFO(getLogger(), "[%s] Action result: Success", this->getName().c_str());
256 onActionSucceeded_(result_msg);
257 postSuccessEvent(result_msg);
258 }
259 else if (resultType == rclcpp_action::ResultCode::ABORTED)
260 {
261 RCLCPP_INFO(getLogger(), "[%s] Action result: Aborted", this->getName().c_str());
262 onActionAborted_(result_msg);
263 postAbortedEvent(result_msg);
264 }
265 else if (resultType == rclcpp_action::ResultCode::CANCELED)
266 {
267 RCLCPP_INFO(getLogger(), "[%s] Action result: Cancelled", this->getName().c_str());
268 onActionCancelled_(result_msg);
269 postCancelledEvent(result_msg);
270 }
271 else
272 {
273 RCLCPP_WARN(
274 getLogger(), "[%s] Action result: Unhandled type: %d", this->getName().c_str(),
275 (int)resultType);
276 }
277 }
278
279 template <typename EvType>
280 void postResultEvent(const WrappedResult & /* result */)
281 {
282 auto * ev = new EvType();
283 RCLCPP_INFO(
284 getLogger(), "[%s] Posting event: %s", this->getName().c_str(),
285 smacc2::demangleSymbol(typeid(ev).name()).c_str());
286 this->postEvent(ev);
287 }
288};
289
290} // namespace client_core_components
291} // namespace smacc2
ISmaccStateMachine * getStateMachine()
virtual std::string getName() const
rclcpp::Logger getLogger() const
rclcpp::Node::SharedPtr getNode()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
std::function< void(std::shared_future< typename GoalHandle::SharedPtr >)> GoalResponseCallback
typename ActionClient::SendGoalOptions SendGoalOptions
std::function< void(const WrappedResult &)> postCancelledEvent
typename GoalHandle::WrappedResult WrappedResult
std::optional< std::shared_future< typename GoalHandle::SharedPtr > > lastRequest_
void onResult(const WrappedResult &result_msg)
boost::signals2::connection onSucceeded(void(T::*callback)(const WrappedResult &), T *object)
CpActionClient(const std::string &actionServerName)
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal, typename smacc2::SmaccSignal< void(const WrappedResult &)>::WeakPtr resultCallback=typename smacc2::SmaccSignal< void(const WrappedResult &)>::WeakPtr())
boost::signals2::connection onCancelled(void(T::*callback)(const WrappedResult &), T *object)
boost::signals2::connection onFeedback(void(T::*callback)(const Feedback &), T *object)
smacc2::SmaccSignal< void(const WrappedResult &)> onActionCancelled_
smacc2::SmaccSignal< void(const Feedback &)> onActionFeedback_
std::function< void(const WrappedResult &)> postSuccessEvent
typename GoalHandle::FeedbackCallback FeedbackCallback
std::optional< std::chrono::milliseconds > serverTimeout
rclcpp_action::Client< ActionType > ActionClient
smacc2::SmaccSignal< void(const WrappedResult &)> onActionSucceeded_
void onFeedback(typename GoalHandle::SharedPtr, const std::shared_ptr< const Feedback > feedback_msg)
std::shared_ptr< ActionClient > getActionClient() const
std::function< void(const WrappedResult &)> postAbortedEvent
boost::signals2::connection onAborted(void(T::*callback)(const WrappedResult &), T *object)
smacc2::SmaccSignal< void(const WrappedResult &)> onActionAborted_
std::function< void(const Feedback &)> postFeedbackEvent
typename GoalHandle::ResultCallback ResultCallback
rclcpp_action::ClientGoalHandle< ActionType > GoalHandle
std::optional< std::shared_future< typename rclcpp_action::Client< ActionType >::CancelResponse::SharedPtr > > lastCancelResponse_
std::string demangleSymbol()