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;
92 client_->wait_for_action_server();
97 auto type = TypeInfo::getTypeInfoFromType<ActionType>();
98 return type->getNonTemplatedTypeName();
101 std::optional<std::shared_future<typename GoalHandle::SharedPtr>>
lastRequest_;
122 template <
typename EvType>
133 template <
typename TOrthogonal,
typename TSourceObject>
157 template <
typename T>
163 template <
typename T>
169 template <
typename T>
175 template <
typename T>
181 template <
typename T>
187 template <
typename T>
249 std::shared_future<typename GoalHandle::SharedPtr>
sendGoal(
270 options.result_callback =
272 const typename rclcpp_action::ClientGoalHandle<ActionType>::WrappedResult & result)
279 getLogger(),
"[" <<
getName() <<
"] Action result callback, getting shared future");
284 << rclcpp_action::to_string(result.goal_id));
299 (*resultCallbackPtr)(result);
328 << this->
client_->get_number_of_ready_clients());
331 "[" <<
getName() <<
"] Waiting it is ready? " <<
client_->action_server_is_ready());
383 typename GoalHandle::SharedPtr ,
402 if (
resultType == rclcpp_action::ResultCode::SUCCEEDED)
408 else if (
resultType == rclcpp_action::ResultCode::ABORTED)
414 else if (
resultType == rclcpp_action::ResultCode::CANCELED)
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
std::optional< std::shared_future< typename CancelResponse::SharedPtr > > lastCancelResponse_
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)