SMACC2
Loading...
Searching...
No Matches
smacc_action_client_base.hpp
Go to the documentation of this file.
1// Copyright 2021 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/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
21#pragma once
22
26
27#include <optional>
28#include <rclcpp_action/rclcpp_action.hpp>
29
30namespace smacc2
31{
32namespace client_bases
33{
34using namespace smacc2::default_events;
35
36template <typename ActionType>
38{
39public:
40 // Inside this macro you can find the typedefs for Goal and other types
41 // ACTION_DEFINITION(ActionType);
42 typedef rclcpp_action::Client<ActionType> ActionClient;
43 // typedef actionlib::SimpleActionClient<ActionType> GoalHandle;
44
45 // typedef typename ActionClient::SimpleDoneCallback SimpleDoneCallback;
46 // typedef typename ActionClient::SimpleActiveCallback SimpleActiveCallback;
47 // typedef typename ActionClient::SimpleFeedbackCallback SimpleFeedbackCallback;
48
49 using Goal = typename ActionClient::Goal;
50 using Feedback = typename ActionClient::Feedback;
51 using GoalHandle = rclcpp_action::ClientGoalHandle<ActionType>;
52 typedef typename GoalHandle::WrappedResult WrappedResult;
53
54 using SendGoalOptions = typename ActionClient::SendGoalOptions;
56 std::function<void(std::shared_future<typename GoalHandle::SharedPtr>)>;
57 using FeedbackCallback = typename GoalHandle::FeedbackCallback;
58 using ResultCallback = typename GoalHandle::ResultCallback;
59 using CancelRequest = typename ActionType::Impl::CancelGoalService::Request;
60 using CancelResponse = typename ActionType::Impl::CancelGoalService::Response;
61 using CancelCallback = std::function<void(typename CancelResponse::SharedPtr)>;
62
63 std::string action_endpoint_;
64 SmaccActionClientBase(std::string actionServerName) : ISmaccActionClient()
65 {
66 action_endpoint_ = actionServerName;
67 }
68
70
72
73 virtual std::shared_ptr<rclcpp_action::ClientBase> getClientBase() override { return client_; }
74
75 void onInitialize() override
76 {
77 if (name_ == "") name_ = smacc2::demangleSymbol(typeid(*this).name());
78 this->client_ = rclcpp_action::create_client<ActionType>(getNode(), action_endpoint_);
79 // RCLCPP_INFO_STREAM(
80 // this->getLogger(),
81 // "Waiting for action server '" << name_ << "' of type: " << demangledTypeName<ActionType>());
82 //client_->wait_for_action_server();
83 }
84
85 static std::string getEventLabel()
86 {
87 auto type = TypeInfo::getTypeInfoFromType<ActionType>();
88 return type->getNonTemplatedTypeName();
89 }
90
91 std::optional<std::shared_future<typename GoalHandle::SharedPtr>> lastRequest_;
92 typename GoalHandle::SharedPtr goalHandle_;
93
96 // smacc2::SmaccSignal<void(const WrappedResult &)> onPreempted_;
97 // smacc2::SmaccSignal<void(const WrappedResult &)> onRejected_;
99
100 // event creation/posting factory functions
101 std::function<void(WrappedResult)> postSuccessEvent;
102 std::function<void(WrappedResult)> postAbortedEvent;
103 // std::function<void(WrappedResult)> postPreemptedEvent;
104 // std::function<void(WrappedResult)> postRejectedEvent;
105 std::function<void(WrappedResult)> postCancelledEvent;
106
107 std::function<void(const Feedback &)> postFeedbackEvent;
108
110 // SimpleActiveCallback active_cb;
112
113 template <typename EvType>
115 {
116 auto * ev = new EvType();
117 // ev->client = this;
118 // ev->resultMessage = *result;
119 RCLCPP_INFO(
120 getLogger(), "Action client Posting EVENT %s", demangleSymbol(typeid(ev).name()).c_str());
121 this->postEvent(ev);
122 }
123
124 template <typename TOrthogonal, typename TSourceObject>
126 {
127 // we create here all the event factory functions capturing the TOrthogonal
128 postSuccessEvent = [this](auto msg)
129 { this->postResultEvent<EvActionSucceeded<TSourceObject, TOrthogonal>>(msg); };
130 postAbortedEvent = [this](auto msg)
131 { this->postResultEvent<EvActionAborted<TSourceObject, TOrthogonal>>(msg); };
132
133 postCancelledEvent = [this](auto msg)
134 { this->postResultEvent<EvActionCancelled<TSourceObject, TOrthogonal>>(msg); };
135 postFeedbackEvent = [this](auto msg)
136 {
137 auto actionFeedbackEvent = new EvActionFeedback<Feedback, TOrthogonal>();
138 actionFeedbackEvent->client = this;
139 actionFeedbackEvent->feedbackMessage = msg;
140 this->postEvent(actionFeedbackEvent);
141 RCLCPP_DEBUG(getLogger(), "[%s] FEEDBACK EVENT", demangleType(typeid(*this)).c_str());
142 };
143
144 done_cb = [this](auto r) { this->onResult(r); };
145 // done_cb = boost::bind(&SmaccActionClientBase<ActionType>::onResult, this, _1, _2);
146 // active_cb;
147 feedback_cb = [this](auto client, auto feedback) { this->onFeedback(client, feedback); };
148 }
149
150 template <typename T>
151 boost::signals2::connection onSucceeded(void (T::*callback)(WrappedResult &), T * object)
152 {
153 return this->getStateMachine()->createSignalConnection(onSucceeded_, callback, object);
154 }
155
156 template <typename T>
157 boost::signals2::connection onSucceeded(std::function<void(WrappedResult &)> callback)
158 {
159 return this->getStateMachine()->createSignalConnection(onSucceeded_, callback);
160 }
161
162 template <typename T>
163 boost::signals2::connection onAborted(void (T::*callback)(WrappedResult &), T * object)
164 {
165 return this->getStateMachine()->createSignalConnection(onAborted_, callback, object);
166 }
167
168 template <typename T>
169 boost::signals2::connection onAborted(std::function<void(WrappedResult &)> callback)
170 {
171 return this->getStateMachine()->createSignalConnection(onAborted_, callback);
172 }
173
174 template <typename T>
175 boost::signals2::connection onCancelled(void (T::*callback)(WrappedResult &), T * object)
176 {
177 return this->getStateMachine()->createSignalConnection(onCancelled_, callback, object);
178 }
179
180 template <typename T>
181 boost::signals2::connection onCancelled(std::function<void(WrappedResult &)> callback)
182 {
183 return this->getStateMachine()->createSignalConnection(onCancelled_, callback);
184 }
185
186 /*
187 template <typename T>
188 boost::signals2::connection onPreempted(void (T::*callback)(WrappedResult &), T *object)
189 {
190 return this->getStateMachine()->createSignalConnection(onPreempted_, callback, object);
191 }
192
193 template <typename T>
194 boost::signals2::connection onPreempted(std::function<void(WrappedResult &)> callback)
195 {
196 return this->getStateMachine()->createSignalConnection(onPreempted_, callback);
197 }
198
199 template <typename T>
200 boost::signals2::connection onRejected(void (T::*callback)(WrappedResult &), T *object)
201 {
202 return this->getStateMachine()->createSignalConnection(onRejected_, callback, object);
203 }
204
205 template <typename T>
206 boost::signals2::connection onRejected(std::function<void(WrappedResult &)> callback)
207 {
208 return this->getStateMachine()->createSignalConnection(onRejected_, callback);
209 }
210 */
211
212 virtual bool cancelGoal() override
213 {
214 if (lastRequest_ && lastRequest_->valid())
215 {
216 rclcpp::spin_until_future_complete(getNode(), *lastRequest_);
217 auto req = lastRequest_->get();
218 RCLCPP_INFO_STREAM(
219 getLogger(), "[" << getName() << "] Cancelling goal. req id: "
220 << rclcpp_action::to_string(req->get_goal_id()));
221 auto cancelresult = client_->async_cancel_goal(req);
222
223 // wait actively
224 rclcpp::spin_until_future_complete(getNode(), cancelresult);
225 //lastRequest_.reset();
226 return true;
227 }
228 else
229 {
230 RCLCPP_ERROR(
231 getLogger(), "%s [at %s]: not connected with actionserver, skipping cancel goal ...",
232 getName().c_str(), getNamespace().c_str());
233 return false;
234 }
235 }
236
237 std::shared_future<typename GoalHandle::SharedPtr> sendGoal(Goal & goal)
238 {
239 // client_->sendGoal(goal, done_cb, active_cb, feedback_cb);
240 // std::shared_future<typename GoalHandle::SharedPtr>
241
242 SendGoalOptions options;
243
244 // GoalResponseCallback
245 // options.goal_response_callback;
246
248 // FeedbackCallback
249 options.feedback_callback = feedback_cb;
250
252 // ResultCallback result_callback;
253 // options.result_callback = done_cb;
254
255 options.result_callback =
256 [this](const typename rclcpp_action::ClientGoalHandle<ActionType>::WrappedResult & result)
257 {
258 // TODO(#1652): a work around until rcl_action interface is updated
259 // if goal ids are not matched, the older goal call this callback so ignore the result
260 // if matched, it must be processed (including aborted)
261 RCLCPP_INFO_STREAM(getLogger(), getName() << ": Result callback, getting shared future");
262 goalHandle_ = lastRequest_->get();
263 RCLCPP_INFO_STREAM(getLogger(), getName() << ": Result CB Check goal id");
264 if (this->goalHandle_->get_goal_id() == result.goal_id)
265 {
266 // goal_result_available_ = true;
267 // result_ = result;
268 RCLCPP_INFO_STREAM(getLogger(), getName() << ": Result CB Goal id matches");
269 done_cb(result);
270 }
271 else
272 {
273 RCLCPP_INFO_STREAM(getLogger(), getName() << ": Result CB Goal id DOES NOT match");
274 }
275 };
276
277 // if (lastRequest_ && lastRequest_->valid())
278 // {
279 // RCLCPP_INFO_STREAM(getLogger(), getName() << ": checking previous request is really finished.");
280 // auto res = this->lastRequest_->get();
281 // RCLCPP_INFO_STREAM(getLogger(), getName() << ": okay");
282 // }
283 // else
284 // {
285 // RCLCPP_INFO_STREAM(getLogger(), getName() << ": no previous request.");
286 // }
287
288 RCLCPP_INFO_STREAM(getLogger(), getName() << ": async send goal.");
289 this->lastRequest_ = this->client_->async_send_goal(goal, options);
290
291 RCLCPP_INFO_STREAM(
292 getLogger(), "[" << getName() << "] Action goal sent to " << this->action_endpoint_
293 << "\": " << std::endl
294 << goal);
295
296 // if (client_->isServerConnected())
297 // {
298 // RCLCPP_INFO_STREAM(getLogger(), getName() << ": Goal sent:" << goal);
299
300 // RCLCPP_INFO_STREAM(getLogger(), getName() << ": Goal Id: " <<
301 // rclcpp_action::to_string(lastRequest_->get()->get_goal_id()));
302
303 RCLCPP_INFO_STREAM(
304 getLogger(), "[" << getName() << "] client ready clients: "
305 << this->client_->get_number_of_ready_clients());
306 RCLCPP_INFO_STREAM(
307 getLogger(),
308 "[" << getName() << "] Waiting it is ready? " << client_->action_server_is_ready());
309
310 // for (auto& gh: this->goal_handles_)
311 // {
312
313 // }
314
315 // RCLCPP_INFO_STREAM(getLogger(), getName() << ": spinning until completed");
316 // if (rclcpp::spin_until_future_complete(this->getNode(), lastRequest_, std::chrono::seconds(2))
317 // !=rclcpp::executor::FutureReturnCode::SUCCESS)
318 // {
319 // throw std::runtime_error("send_goal failed");
320 // }
321
322 // goalHandle_ = lastRequest_->get();
323 // if (!goalHandle_) {
324 // throw std::runtime_error("Goal was rejected by the action server");
325 // }
326
327 // }
328 // else
329 // {
330 // RCLCPP_ERROR(getLogger(),"%s [at %s]: not connected with actionserver, skipping goal request
331 // ...", getName().c_str(), getNamespace().c_str());
332 // //client_->waitForServer();
333 // }
334
335 return *lastRequest_;
336 }
337
338protected:
339 typename ActionClient::SharedPtr client_;
340
342 typename GoalHandle::SharedPtr /*goalhandle*/,
343 const std::shared_ptr<const Feedback> feedback_msg)
344 {
345 postFeedbackEvent(*feedback_msg);
346 }
347
348 void onResult(const WrappedResult & result_msg)
349 {
350 // auto *actionResultEvent = new EvActionResult<TDerived>();
351 // actionResultEvent->client = this;
352 // actionResultEvent->resultMessage = *result_msg;
353
354 // const auto &resultType = this->getState();
355 const auto & resultType = result_msg.code;
356
357 RCLCPP_INFO_STREAM(
358 getLogger(), "[" << this->getName() << "] request result of request ["
359 << rclcpp_action::to_string(result_msg.goal_id) << "]: " << (int)resultType);
360
361 if (resultType == rclcpp_action::ResultCode::SUCCEEDED)
362 {
363 RCLCPP_INFO(getLogger(), "[%s] request result: Success", this->getName().c_str());
364 onSucceeded_(result_msg);
365 postSuccessEvent(result_msg);
366 }
367 else if (resultType == rclcpp_action::ResultCode::ABORTED)
368 {
369 RCLCPP_INFO(getLogger(), "[%s] request result: Aborted", this->getName().c_str());
370 onAborted_(result_msg);
371 postAbortedEvent(result_msg);
372 }
373 else if (resultType == rclcpp_action::ResultCode::CANCELED)
374 {
375 RCLCPP_INFO(getLogger(), "[%s] request result: Cancelled", this->getName().c_str());
376 onCancelled_(result_msg);
377 postCancelledEvent(result_msg);
378 }
379 /*
380 else if (resultType == actionlib::SimpleClientGoalState::REJECTED)
381 {
382 RCLCPP_INFO(getLogger(),"[%s] request result: Rejected", this->getName().c_str());
383 onRejected_(result_msg);
384 postRejectedEvent(result_msg);
385 }
386 else if (resultType == actionlib::SimpleClientGoalState::PREEMPTED)
387 {
388 RCLCPP_INFO(getLogger(),"[%s] request result: Preempted", this->getName().c_str());
389 onPreempted_(result_msg);
390 postPreemptedEvent(result_msg);
391 }*/
392 else
393 {
394 RCLCPP_INFO(
395 getLogger(), "[%s] request result: NOT HANDLED TYPE: %d", this->getName().c_str(),
396 (int)resultType);
397 }
398 }
399};
400
401} // namespace client_bases
402
403} // namespace smacc2
rclcpp::Node::SharedPtr getNode()
Definition: client.cpp:60
ISmaccStateMachine * getStateMachine()
rclcpp::Logger getLogger()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
typename ActionType::Impl::CancelGoalService::Response CancelResponse
typename ActionType::Impl::CancelGoalService::Request CancelRequest
boost::signals2::connection onAborted(void(T::*callback)(WrappedResult &), T *object)
std::function< void(std::shared_future< typename GoalHandle::SharedPtr >)> GoalResponseCallback
std::function< void(typename CancelResponse::SharedPtr)> CancelCallback
typename ActionClient::SendGoalOptions SendGoalOptions
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)
void onFeedback(typename GoalHandle::SharedPtr, const std::shared_ptr< const Feedback > feedback_msg)
virtual std::shared_ptr< rclcpp_action::ClientBase > getClientBase() override
rclcpp_action::Client< ActionType > ActionClient
std::function< void(WrappedResult)> postCancelledEvent
smacc2::SmaccSignal< void(const WrappedResult &)> onSucceeded_
std::function< void(WrappedResult)> postSuccessEvent
boost::signals2::connection onSucceeded(std::function< void(WrappedResult &)> callback)
boost::signals2::connection onSucceeded(void(T::*callback)(WrappedResult &), T *object)
smacc2::SmaccSignal< void(const WrappedResult &)> onAborted_
boost::signals2::connection onCancelled(std::function< void(WrappedResult &)> callback)
rclcpp_action::ClientGoalHandle< ActionType > GoalHandle
std::function< void(WrappedResult)> postAbortedEvent
void onResult(const WrappedResult &result_msg)
std::function< void(const Feedback &)> postFeedbackEvent
smacc2::SmaccSignal< void(const WrappedResult &)> onCancelled_
boost::signals2::connection onCancelled(void(T::*callback)(WrappedResult &), T *object)
typename GoalHandle::ResultCallback ResultCallback
boost::signals2::connection onAborted(std::function< void(WrappedResult &)> callback)
std::optional< std::shared_future< typename GoalHandle::SharedPtr > > lastRequest_
typename GoalHandle::FeedbackCallback FeedbackCallback
std::string demangleSymbol()
std::string demangleType(const std::type_info *tinfo)