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
64
65 std::string action_endpoint_;
66 SmaccActionClientBase(std::string actionServerName) : ISmaccActionClient()
67 {
68 action_endpoint_ = actionServerName;
69 }
70
72
74
75 virtual std::shared_ptr<rclcpp_action::ClientBase> getClientBase() override { return client_; }
76
77 void onInitialize() override
78 {
79 if (name_ == "") name_ = smacc2::demangleSymbol(typeid(*this).name());
80 this->client_ = rclcpp_action::create_client<ActionType>(getNode(), action_endpoint_);
81 // RCLCPP_INFO_STREAM(
82 // this->getLogger(),
83 // "Waiting for action server '" << name_ << "' of type: " << demangledTypeName<ActionType>());
84 //client_->wait_for_action_server();
85 }
86
87 static std::string getEventLabel()
88 {
89 auto type = TypeInfo::getTypeInfoFromType<ActionType>();
90 return type->getNonTemplatedTypeName();
91 }
92
93 std::optional<std::shared_future<typename GoalHandle::SharedPtr>> lastRequest_;
94 // typename GoalHandle::SharedPtr goalHandle_;
95
98 // SmaccActionResultSignal onPreempted_;
99 // SmaccActionResultSignal onRejected_;
101
102 // event creation/posting factory functions
103 std::function<void(WrappedResult)> postSuccessEvent;
104 std::function<void(WrappedResult)> postAbortedEvent;
105 std::function<void(WrappedResult)> postCancelledEvent;
106 // std::function<void(WrappedResult)> postPreemptedEvent;
107 // std::function<void(WrappedResult)> postRejectedEvent;
108
109 std::function<void(const Feedback &)> postFeedbackEvent;
110
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
136 postFeedbackEvent = [this](auto msg)
137 {
138 auto actionFeedbackEvent = new EvActionFeedback<Feedback, TOrthogonal>();
139 actionFeedbackEvent->client = this;
140 actionFeedbackEvent->feedbackMessage = msg;
141 this->postEvent(actionFeedbackEvent);
142 RCLCPP_DEBUG(getLogger(), "[%s] FEEDBACK EVENT", demangleType(typeid(*this)).c_str());
143 };
144
145 // result_cb = [this](auto r) { this->onResult(r); };
146 // result_cb = boost::bind(&SmaccActionClientBase<ActionType>::onResult, this, _1, _2);
147 // active_cb;
148
149 feedback_cb = [this](auto client, auto feedback) { this->onFeedback(client, feedback); };
150 }
151
152 template <typename T>
153 boost::signals2::connection onSucceeded(void (T::*callback)(WrappedResult &), T * object)
154 {
155 return this->getStateMachine()->createSignalConnection(onSucceeded_, callback, object);
156 }
157
158 template <typename T>
159 boost::signals2::connection onSucceeded(std::function<void(WrappedResult &)> callback)
160 {
161 return this->getStateMachine()->createSignalConnection(onSucceeded_, callback);
162 }
163
164 template <typename T>
165 boost::signals2::connection onAborted(void (T::*callback)(WrappedResult &), T * object)
166 {
167 return this->getStateMachine()->createSignalConnection(onAborted_, callback, object);
168 }
169
170 template <typename T>
171 boost::signals2::connection onAborted(std::function<void(WrappedResult &)> callback)
172 {
173 return this->getStateMachine()->createSignalConnection(onAborted_, callback);
174 }
175
176 template <typename T>
177 boost::signals2::connection onCancelled(void (T::*callback)(WrappedResult &), T * object)
178 {
179 return this->getStateMachine()->createSignalConnection(onCancelled_, callback, object);
180 }
181
182 template <typename T>
183 boost::signals2::connection onCancelled(std::function<void(WrappedResult &)> callback)
184 {
185 return this->getStateMachine()->createSignalConnection(onCancelled_, callback);
186 }
187
188 /*
189 template <typename T>
190 boost::signals2::connection onPreempted(void (T::*callback)(WrappedResult &), T *object)
191 {
192 return this->getStateMachine()->createSignalConnection(onPreempted_, callback, object);
193 }
194
195 template <typename T>
196 boost::signals2::connection onPreempted(std::function<void(WrappedResult &)> callback)
197 {
198 return this->getStateMachine()->createSignalConnection(onPreempted_, callback);
199 }
200
201 template <typename T>
202 boost::signals2::connection onRejected(void (T::*callback)(WrappedResult &), T *object)
203 {
204 return this->getStateMachine()->createSignalConnection(onRejected_, callback, object);
205 }
206
207 template <typename T>
208 boost::signals2::connection onRejected(std::function<void(WrappedResult &)> callback)
209 {
210 return this->getStateMachine()->createSignalConnection(onRejected_, callback);
211 }
212 */
213
214 virtual bool cancelGoal() override
215 {
216 auto fut = this->client_->async_cancel_all_goals();
217 fut.wait();
218
219 // if (lastRequest_ && lastRequest_->valid())
220 // {
221
222 // // rclcpp::spin_until_future_complete(getNode(), *lastRequest_);
223 // auto req = lastRequest_->get();
224 // RCLCPP_INFO_STREAM(
225 // getLogger(), "[" << getName() << "] Cancelling goal. req id: "
226 // << rclcpp_action::to_string(req->get_goal_id()));
227 // auto cancelresult = client_->async_cancel_goal(req);
228
229 // // wait actively
230 // // rclcpp::spin_until_future_complete(getNode(), cancelresult);
231 // //lastRequest_.reset();
232 // return true;
233 // }
234 // else
235 // {
236 // RCLCPP_ERROR(
237 // getLogger(), "%s [at %s]: not connected with actionserver, skipping cancel goal ...",
238 // getName().c_str(), getNamespace().c_str());
239 // return false;
240 // }
241
242 return true;
243 }
244
245 std::shared_future<typename GoalHandle::SharedPtr> sendGoal(
246 Goal & goal, typename SmaccActionResultSignal::WeakPtr resultCallback =
248 //ResultCallback resultCallback = nullptr) // bug related with the cancel action and the issue
249 {
250 // client_->sendGoal(goal, result_cb, active_cb, feedback_cb);
251 // std::shared_future<typename GoalHandle::SharedPtr>
252
253 SendGoalOptions options;
254
255 // GoalResponseCallback
256 // options.goal_response_callback;
257
259 // FeedbackCallback
260 options.feedback_callback = feedback_cb;
261
263 // ResultCallback result_callback;
264 // options.result_callback = result_cb;
265
266 options.result_callback =
267 [this, resultCallback](
268 const typename rclcpp_action::ClientGoalHandle<ActionType>::WrappedResult & result)
269 {
270 // TODO(#1652): a work around until rcl_action interface is updated
271 // if goal ids are not matched, the older goa call this callback so ignore the result
272 // if matched, it must be processed (including aborted)
273
274 RCLCPP_INFO_STREAM(
275 getLogger(), "[" << getName() << "] Action result callback, getting shared future");
276 // auto goalHandle = result->get();
277 // goalHandle_ = lastRequest_->get();
278 RCLCPP_INFO_STREAM(
279 getLogger(), "[" << getName() << "] Action client Result goal id: "
280 << rclcpp_action::to_string(result.goal_id));
281
282 // if (goalHandle_->get_goal_id() == result.goal_id)
283 // {
284 // // goal_result_available_ = true;
285 // // result_ = result;
286 // RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] Result CB Goal id matches with last request");
287
288 auto resultCallbackPtr = resultCallback.lock();
289
290 if (resultCallbackPtr != nullptr)
291 {
292 RCLCPP_INFO_STREAM(
293 getLogger(), "[" << getName() << "] Result CB calling user callback:"
294 << demangleSymbol(typeid(*resultCallbackPtr).name()));
295 (*resultCallbackPtr)(result);
296 }
297 else
298 {
299 RCLCPP_INFO_STREAM(
300 getLogger(), "[" << getName() << "] Result CB calling default callback");
301 this->onResult(result);
302 }
303
304 // }
305 // else
306 // {
307 // RCLCPP_ERROR_STREAM(getLogger(), "[" << getName() << "] Result CB Goal id DOES NOT match with last request. Skipping, incorrect behavior.");
308 // }
309 };
310
311 // if (lastRequest_ && lastRequest_->valid())
312 // {
313 // RCLCPP_INFO_STREAM(getLogger(), getName() << ": checking previous request is really finished.");
314 // auto res = this->lastRequest_->get();
315 // RCLCPP_INFO_STREAM(getLogger(), getName() << ": okay");
316 // }
317 // else
318 // {
319 // RCLCPP_INFO_STREAM(getLogger(), getName() << ": no previous request.");
320 // }
321
322 RCLCPP_INFO_STREAM(
323 getLogger(), "[" << getName() << "] client ready clients: "
324 << this->client_->get_number_of_ready_clients());
325 RCLCPP_INFO_STREAM(
326 getLogger(),
327 "[" << getName() << "] Waiting it is ready? " << client_->action_server_is_ready());
328
329 RCLCPP_INFO_STREAM(getLogger(), getName() << ": async send goal.");
330 auto lastRequest = this->client_->async_send_goal(goal, options);
331 this->lastRequest_ = lastRequest;
332
333 RCLCPP_INFO_STREAM(
334 getLogger(),
335 "["
336 << getName()
337 << "] Action request "
338 // << rclcpp_action::to_string(this->goalHandle_->get_goal_id()) <<". Goal sent to " << this->action_endpoint_
339 << "\": " << std::endl
340 << goal);
341
342 // if (client_->isServerConnected())
343 // {
344 // RCLCPP_INFO_STREAM(getLogger(), getName() << ": Goal sent:" << goal);
345
346 // RCLCPP_INFO_STREAM(getLogger(), getName() << ": Goal Id: " <<
347 // rclcpp_action::to_string(lastRequest_->get()->get_goal_id()));
348
349 // for (auto& gh: this->goal_handles_)
350 // {
351
352 // }
353
354 // RCLCPP_INFO_STREAM(getLogger(), getName() << ": spinning until completed");
355 // if (rclcpp::spin_until_future_complete(this->getNode(), lastRequest_, std::chrono::seconds(2))
356 // !=rclcpp::executor::FutureReturnCode::SUCCESS)
357 // {
358 // throw std::runtime_error("send_goal failed");
359 // }
360
361 // goalHandle_ = lastRequest_->get();
362 // if (!goalHandle_) {
363 // throw std::runtime_error("Goal was rejected by the action server");
364 // }
365
366 // }
367 // else
368 // {
369 // RCLCPP_ERROR(getLogger(),"%s [at %s]: not connected with actionserver, skipping goal request
370 // ...", getName().c_str(), getNamespace().c_str());
371 // //client_->waitForServer();
372 // }
373
374 return lastRequest;
375 }
376
377protected:
378 typename ActionClient::SharedPtr client_;
379
381 typename GoalHandle::SharedPtr /*goalhandle*/,
382 const std::shared_ptr<const Feedback> feedback_msg)
383 {
384 postFeedbackEvent(*feedback_msg);
385 }
386
387 void onResult(const WrappedResult & result_msg)
388 {
389 // auto *actionResultEvent = new EvActionResult<TDerived>();
390 // actionResultEvent->client = this;
391 // actionResultEvent->resultMessage = *result_msg;
392
393 // const auto &resultType = this->getState();
394 const auto & resultType = result_msg.code;
395
396 RCLCPP_INFO_STREAM(
397 getLogger(), "[" << this->getName() << "] response result ["
398 << rclcpp_action::to_string(result_msg.goal_id) << "]: " << (int)resultType);
399
400 if (resultType == rclcpp_action::ResultCode::SUCCEEDED)
401 {
402 RCLCPP_INFO(getLogger(), "[%s] request result: Success", this->getName().c_str());
403 onSucceeded_(result_msg);
404 postSuccessEvent(result_msg);
405 }
406 else if (resultType == rclcpp_action::ResultCode::ABORTED)
407 {
408 RCLCPP_INFO(getLogger(), "[%s] request result: Aborted", this->getName().c_str());
409 onAborted_(result_msg);
410 postAbortedEvent(result_msg);
411 }
412 else if (resultType == rclcpp_action::ResultCode::CANCELED)
413 {
414 RCLCPP_INFO(getLogger(), "[%s] request result: Cancelled", this->getName().c_str());
415 onCancelled_(result_msg);
416 postCancelledEvent(result_msg);
417 }
418 /*
419 else if (resultType == actionlib::SimpleClientGoalState::REJECTED)
420 {
421 RCLCPP_INFO(getLogger(),"[%s] request result: Rejected", this->getName().c_str());
422 onRejected_(result_msg);
423 postRejectedEvent(result_msg);
424 }
425 else if (resultType == actionlib::SimpleClientGoalState::PREEMPTED)
426 {
427 RCLCPP_INFO(getLogger(),"[%s] request result: Preempted", this->getName().c_str());
428 onPreempted_(result_msg);
429 postPreemptedEvent(result_msg);
430 }*/
431 else
432 {
433 RCLCPP_INFO(
434 getLogger(), "[%s] request result: NOT HANDLED TYPE: %d", this->getName().c_str(),
435 (int)resultType);
436 }
437 }
438};
439
440} // namespace client_bases
441
442} // 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)
std::weak_ptr< SmaccSignal< void(const WrappedResult &), optional_last_value< typename boost::function_traits< void(const WrappedResult &) >::result_type >, int, std::less< int >, function< void(const WrappedResult &) >, typename extended_signature< function_traits< void(const WrappedResult &) >::arity, void(const WrappedResult &) >::function_type, boost::signals2::mutex > > WeakPtr
typename ActionType::Impl::CancelGoalService::Response CancelResponse
smacc2::SmaccSignal< void(const WrappedResult &)> SmaccActionResultSignal
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
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
std::function< void(WrappedResult)> postSuccessEvent
boost::signals2::connection onSucceeded(std::function< void(WrappedResult &)> callback)
boost::signals2::connection onSucceeded(void(T::*callback)(WrappedResult &), T *object)
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
boost::signals2::connection onCancelled(void(T::*callback)(WrappedResult &), T *object)
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal, typename SmaccActionResultSignal::WeakPtr resultCallback=typename SmaccActionResultSignal::WeakPtr())
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)