27#include <rclcpp_action/rclcpp_action.hpp>
31namespace client_core_components
35template <
typename 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>;
48 std::function<void(std::shared_future<typename GoalHandle::SharedPtr>)>;
78 std::shared_future<typename GoalHandle::SharedPtr>
sendGoal(
90 options.result_callback = [
this, resultCallback](
const WrappedResult & result)
96 << rclcpp_action::to_string(result.goal_id));
98 auto resultCallbackPtr = resultCallback.lock();
99 if (resultCallbackPtr !=
nullptr)
101 RCLCPP_INFO_STREAM(
getLogger(),
"[" << this->
getName() <<
"] Calling user result callback");
102 (*resultCallbackPtr)(result);
114 "[" << this->
getName() <<
"] Sending goal to action server: " << (
long)
client_.get());
116 auto goalFuture =
client_->async_send_goal(goal, options);
128 RCLCPP_INFO_STREAM(
getLogger(),
"[" << this->
getName() <<
"] Cancelling current goal");
130 auto cancelFuture =
client_->async_cancel_all_goals();
136 RCLCPP_WARN_STREAM(
getLogger(),
"[" << this->
getName() <<
"] No active goal to cancel");
149 "[" << this->
getName() <<
"] Waiting for action server: " << *actionServerName);
150 client_->wait_for_action_server();
159 RCLCPP_ERROR_STREAM(
getLogger(),
"[" << this->
getName() <<
"] Action server name not set!");
165 "[" << this->
getName() <<
"] Initializing action client for: " << *actionServerName);
170 "[" << this->
getName() <<
"] DONE Initializing action client for: " << *actionServerName);
177 template <
typename TOrthogonal,
typename TSourceObject>
194 actionFeedbackEvent->feedbackMessage = feedback;
201 template <
typename T>
207 template <
typename T>
213 template <
typename T>
219 template <
typename T>
229 std::shared_ptr<ActionClient>
client_ =
nullptr;
230 std::optional<std::shared_future<typename GoalHandle::SharedPtr>>
lastRequest_;
232 std::shared_future<typename rclcpp_action::Client<ActionType>::CancelResponse::SharedPtr>>
238 typename GoalHandle::SharedPtr ,
239 const std::shared_ptr<const Feedback> feedback_msg)
247 const auto & resultType = result_msg.code;
251 << rclcpp_action::to_string(result_msg.goal_id) <<
"]: " << (
int)resultType);
253 if (resultType == rclcpp_action::ResultCode::SUCCEEDED)
255 RCLCPP_INFO(
getLogger(),
"[%s] Action result: Success", this->
getName().c_str());
259 else if (resultType == rclcpp_action::ResultCode::ABORTED)
261 RCLCPP_INFO(
getLogger(),
"[%s] Action result: Aborted", this->
getName().c_str());
265 else if (resultType == rclcpp_action::ResultCode::CANCELED)
267 RCLCPP_INFO(
getLogger(),
"[%s] Action result: Cancelled", this->
getName().c_str());
274 getLogger(),
"[%s] Action result: Unhandled type: %d", this->
getName().c_str(),
279 template <
typename EvType>
282 auto * ev =
new EvType();
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::string > actionServerName
void onComponentInitialization()
smacc2::SmaccSignal< void()> onGoalAccepted_
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)
virtual ~CpActionClient()=default
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)
FeedbackCallback feedbackCallback_
smacc2::SmaccSignal< void(const WrappedResult &)> onActionCancelled_
smacc2::SmaccSignal< void(const Feedback &)> onActionFeedback_
typename ActionType::Feedback Feedback
typename ActionType::Result Result
smacc2::SmaccSignal< void()> onGoalRejected_
std::function< void(const WrappedResult &)> postSuccessEvent
typename GoalHandle::FeedbackCallback FeedbackCallback
std::optional< std::chrono::milliseconds > serverTimeout
void onInitialize() override
rclcpp_action::Client< ActionType > ActionClient
smacc2::SmaccSignal< void(const WrappedResult &)> onActionSucceeded_
std::shared_ptr< ActionClient > client_
void onFeedback(typename GoalHandle::SharedPtr, const std::shared_ptr< const Feedback > feedback_msg)
bool isServerReady() const
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
typename ActionType::Goal Goal
void postResultEvent(const WrappedResult &)
std::optional< std::shared_future< typename rclcpp_action::Client< ActionType >::CancelResponse::SharedPtr > > lastCancelResponse_
std::string demangleSymbol()