28#include <rclcpp_action/rclcpp_action.hpp>
36template <
typename ActionType>
49 using Goal =
typename ActionClient::Goal;
50 using Feedback =
typename ActionClient::Feedback;
51 using GoalHandle = rclcpp_action::ClientGoalHandle<ActionType>;
56 std::function<void(std::shared_future<typename GoalHandle::SharedPtr>)>;
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)>;
89 auto type = TypeInfo::getTypeInfoFromType<ActionType>();
90 return type->getNonTemplatedTypeName();
93 std::optional<std::shared_future<typename GoalHandle::SharedPtr>>
lastRequest_;
113 template <
typename EvType>
116 auto * ev =
new EvType();
124 template <
typename TOrthogonal,
typename TSourceObject>
129 { this->postResultEvent<EvActionSucceeded<TSourceObject, TOrthogonal>>(msg); };
131 { this->postResultEvent<EvActionAborted<TSourceObject, TOrthogonal>>(msg); };
134 { this->postResultEvent<EvActionCancelled<TSourceObject, TOrthogonal>>(msg); };
139 actionFeedbackEvent->client =
this;
140 actionFeedbackEvent->feedbackMessage = msg;
152 template <
typename T>
158 template <
typename T>
164 template <
typename T>
170 template <
typename T>
176 template <
typename T>
182 template <
typename T>
216 auto fut = this->
client_->async_cancel_all_goals();
245 std::shared_future<typename GoalHandle::SharedPtr>
sendGoal(
266 options.result_callback =
267 [
this, resultCallback](
268 const typename rclcpp_action::ClientGoalHandle<ActionType>::WrappedResult & result)
275 getLogger(),
"[" <<
getName() <<
"] Action result callback, getting shared future");
280 << rclcpp_action::to_string(result.goal_id));
288 auto resultCallbackPtr = resultCallback.lock();
290 if (resultCallbackPtr !=
nullptr)
295 (*resultCallbackPtr)(result);
324 << this->
client_->get_number_of_ready_clients());
327 "[" <<
getName() <<
"] Waiting it is ready? " <<
client_->action_server_is_ready());
330 auto lastRequest = this->
client_->async_send_goal(goal, options);
331 this->lastRequest_ = lastRequest;
337 <<
"] Action request "
339 <<
"\": " << std::endl
381 typename GoalHandle::SharedPtr ,
382 const std::shared_ptr<const Feedback> feedback_msg)
394 const auto & resultType = result_msg.code;
398 << rclcpp_action::to_string(result_msg.goal_id) <<
"]: " << (
int)resultType);
400 if (resultType == rclcpp_action::ResultCode::SUCCEEDED)
402 RCLCPP_INFO(
getLogger(),
"[%s] request result: Success", this->
getName().c_str());
406 else if (resultType == rclcpp_action::ResultCode::ABORTED)
408 RCLCPP_INFO(
getLogger(),
"[%s] request result: Aborted", this->
getName().c_str());
412 else if (resultType == rclcpp_action::ResultCode::CANCELED)
414 RCLCPP_INFO(
getLogger(),
"[%s] request result: Cancelled", this->
getName().c_str());
434 getLogger(),
"[%s] request result: NOT HANDLED TYPE: %d", this->
getName().c_str(),
rclcpp::Node::SharedPtr getNode()
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
virtual std::string getName() const
SmaccActionResultSignal onCancelled_
typename ActionType::Impl::CancelGoalService::Response CancelResponse
typename ActionClient::Feedback Feedback
smacc2::SmaccSignal< void(const WrappedResult &)> SmaccActionResultSignal
typename ActionType::Impl::CancelGoalService::Request CancelRequest
SmaccActionResultSignal onAborted_
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
std::string action_endpoint_
typename ActionClient::SendGoalOptions SendGoalOptions
virtual ~SmaccActionClientBase()
static std::string getEventLabel()
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)
void onOrthogonalAllocation()
FeedbackCallback feedback_cb
void onInitialize() override
ActionClient::SharedPtr client_
boost::signals2::connection onCancelled(std::function< void(WrappedResult &)> callback)
rclcpp_action::ClientGoalHandle< ActionType > GoalHandle
SmaccActionClientBase(std::string actionServerName)
std::function< void(WrappedResult)> postAbortedEvent
void onResult(const WrappedResult &result_msg)
std::function< void(const Feedback &)> postFeedbackEvent
typename ActionClient::Goal Goal
GoalHandle::WrappedResult WrappedResult
boost::signals2::connection onCancelled(void(T::*callback)(WrappedResult &), T *object)
virtual bool cancelGoal() override
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal, typename SmaccActionResultSignal::WeakPtr resultCallback=typename SmaccActionResultSignal::WeakPtr())
typename GoalHandle::ResultCallback ResultCallback
void postResultEvent(WrappedResult &)
boost::signals2::connection onAborted(std::function< void(WrappedResult &)> callback)
std::optional< std::shared_future< typename GoalHandle::SharedPtr > > lastRequest_
typename GoalHandle::FeedbackCallback FeedbackCallback
SmaccActionResultSignal onSucceeded_
std::string demangleSymbol()
std::string demangleType(const std::type_info *tinfo)