SMACC2
Loading...
Searching...
No Matches
smacc2::client_core_components::CpActionClient< ActionType > Class Template Reference

#include <cp_action_client.hpp>

Inheritance diagram for smacc2::client_core_components::CpActionClient< ActionType >:
Inheritance graph
Collaboration diagram for smacc2::client_core_components::CpActionClient< ActionType >:
Collaboration graph

Public Types

using ActionClient = rclcpp_action::Client<ActionType>
 
using Goal = typename ActionType::Goal
 
using Feedback = typename ActionType::Feedback
 
using Result = typename ActionType::Result
 
using GoalHandle = rclcpp_action::ClientGoalHandle<ActionType>
 
using WrappedResult = typename GoalHandle::WrappedResult
 
using SendGoalOptions = typename ActionClient::SendGoalOptions
 
using GoalResponseCallback
 
using FeedbackCallback = typename GoalHandle::FeedbackCallback
 
using ResultCallback = typename GoalHandle::ResultCallback
 

Public Member Functions

 CpActionClient ()=default
 
 CpActionClient (const std::string &actionServerName)
 
virtual ~CpActionClient ()=default
 
std::shared_future< typename GoalHandle::SharedPtr > sendGoal (Goal &goal, typename smacc2::SmaccSignal< void(const WrappedResult &)>::WeakPtr resultCallback=typename smacc2::SmaccSignal< void(const WrappedResult &)>::WeakPtr())
 
bool cancelGoal ()
 
bool isServerReady () const
 
void waitForServer ()
 
void onInitialize () override
 
template<typename TOrthogonal , typename TSourceObject >
void onComponentInitialization ()
 
template<typename T >
boost::signals2::connection onSucceeded (void(T::*callback)(const WrappedResult &), T *object)
 
template<typename T >
boost::signals2::connection onAborted (void(T::*callback)(const WrappedResult &), T *object)
 
template<typename T >
boost::signals2::connection onCancelled (void(T::*callback)(const WrappedResult &), T *object)
 
template<typename T >
boost::signals2::connection onFeedback (void(T::*callback)(const Feedback &), T *object)
 
std::shared_ptr< ActionClientgetActionClient () const
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Public Attributes

std::optional< std::string > actionServerName
 
std::optional< std::chrono::milliseconds > serverTimeout
 
smacc2::SmaccSignal< void(const WrappedResult &)> onActionSucceeded_
 
smacc2::SmaccSignal< void(const WrappedResult &)> onActionAborted_
 
smacc2::SmaccSignal< void(const WrappedResult &)> onActionCancelled_
 
smacc2::SmaccSignal< void(const Feedback &)> onActionFeedback_
 
smacc2::SmaccSignal< void()> onGoalAccepted_
 
smacc2::SmaccSignal< void()> onGoalRejected_
 
std::function< void(const WrappedResult &)> postSuccessEvent
 
std::function< void(const WrappedResult &)> postAbortedEvent
 
std::function< void(const WrappedResult &)> postCancelledEvent
 
std::function< void(const Feedback &)> postFeedbackEvent
 

Private Member Functions

void onFeedback (typename GoalHandle::SharedPtr, const std::shared_ptr< const Feedback > feedback_msg)
 
void onResult (const WrappedResult &result_msg)
 
template<typename EvType >
void postResultEvent (const WrappedResult &)
 

Private Attributes

std::shared_ptr< ActionClientclient_ = nullptr
 
std::optional< std::shared_future< typename GoalHandle::SharedPtr > > lastRequest_
 
std::optional< std::shared_future< typename rclcpp_action::Client< ActionType >::CancelResponse::SharedPtr > > lastCancelResponse_
 
FeedbackCallback feedbackCallback_
 
std::mutex actionMutex_
 

Additional Inherited Members

- Protected Member Functions inherited from smacc2::ISmaccComponent
template<typename TOrthogonal , typename TClient >
void onComponentInitialization ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist)
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingComponent (TArgs... targs)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingNamedComponent (std::string name, TArgs... targs)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger () const
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

template<typename ActionType>
class smacc2::client_core_components::CpActionClient< ActionType >

Definition at line 36 of file cp_action_client.hpp.

Member Typedef Documentation

◆ ActionClient

template<typename ActionType >
using smacc2::client_core_components::CpActionClient< ActionType >::ActionClient = rclcpp_action::Client<ActionType>

Definition at line 40 of file cp_action_client.hpp.

◆ Feedback

template<typename ActionType >
using smacc2::client_core_components::CpActionClient< ActionType >::Feedback = typename ActionType::Feedback

Definition at line 42 of file cp_action_client.hpp.

◆ FeedbackCallback

template<typename ActionType >
using smacc2::client_core_components::CpActionClient< ActionType >::FeedbackCallback = typename GoalHandle::FeedbackCallback

Definition at line 49 of file cp_action_client.hpp.

◆ Goal

template<typename ActionType >
using smacc2::client_core_components::CpActionClient< ActionType >::Goal = typename ActionType::Goal

Definition at line 41 of file cp_action_client.hpp.

◆ GoalHandle

template<typename ActionType >
using smacc2::client_core_components::CpActionClient< ActionType >::GoalHandle = rclcpp_action::ClientGoalHandle<ActionType>

Definition at line 44 of file cp_action_client.hpp.

◆ GoalResponseCallback

template<typename ActionType >
using smacc2::client_core_components::CpActionClient< ActionType >::GoalResponseCallback
Initial value:
std::function<void(std::shared_future<typename GoalHandle::SharedPtr>)>

Definition at line 47 of file cp_action_client.hpp.

◆ Result

template<typename ActionType >
using smacc2::client_core_components::CpActionClient< ActionType >::Result = typename ActionType::Result

Definition at line 43 of file cp_action_client.hpp.

◆ ResultCallback

template<typename ActionType >
using smacc2::client_core_components::CpActionClient< ActionType >::ResultCallback = typename GoalHandle::ResultCallback

Definition at line 50 of file cp_action_client.hpp.

◆ SendGoalOptions

template<typename ActionType >
using smacc2::client_core_components::CpActionClient< ActionType >::SendGoalOptions = typename ActionClient::SendGoalOptions

Definition at line 46 of file cp_action_client.hpp.

◆ WrappedResult

template<typename ActionType >
using smacc2::client_core_components::CpActionClient< ActionType >::WrappedResult = typename GoalHandle::WrappedResult

Definition at line 45 of file cp_action_client.hpp.

Constructor & Destructor Documentation

◆ CpActionClient() [1/2]

template<typename ActionType >
smacc2::client_core_components::CpActionClient< ActionType >::CpActionClient ( )
default

◆ CpActionClient() [2/2]

template<typename ActionType >
smacc2::client_core_components::CpActionClient< ActionType >::CpActionClient ( const std::string & actionServerName)
inline

Definition at line 73 of file cp_action_client.hpp.

◆ ~CpActionClient()

template<typename ActionType >
virtual smacc2::client_core_components::CpActionClient< ActionType >::~CpActionClient ( )
virtualdefault

Member Function Documentation

◆ cancelGoal()

template<typename ActionType >
bool smacc2::client_core_components::CpActionClient< ActionType >::cancelGoal ( )
inline

Definition at line 122 of file cp_action_client.hpp.

123 {
124 std::lock_guard<std::mutex> lock(actionMutex_);
125
126 if (lastRequest_ && lastRequest_->valid())
127 {
128 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] Cancelling current goal");
129
130 auto cancelFuture = client_->async_cancel_all_goals();
131 lastCancelResponse_ = cancelFuture;
132 return true;
133 }
134 else
135 {
136 RCLCPP_WARN_STREAM(getLogger(), "[" << this->getName() << "] No active goal to cancel");
137 return false;
138 }
139 }
virtual std::string getName() const
rclcpp::Logger getLogger() const
std::optional< std::shared_future< typename GoalHandle::SharedPtr > > lastRequest_
std::optional< std::shared_future< typename rclcpp_action::Client< ActionType >::CancelResponse::SharedPtr > > lastCancelResponse_

References smacc2::client_core_components::CpActionClient< ActionType >::actionMutex_, smacc2::client_core_components::CpActionClient< ActionType >::client_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::client_core_components::CpActionClient< ActionType >::lastCancelResponse_, and smacc2::client_core_components::CpActionClient< ActionType >::lastRequest_.

Here is the call graph for this function:

◆ getActionClient()

template<typename ActionType >
std::shared_ptr< ActionClient > smacc2::client_core_components::CpActionClient< ActionType >::getActionClient ( ) const
inline

Definition at line 226 of file cp_action_client.hpp.

226{ return client_; }

References smacc2::client_core_components::CpActionClient< ActionType >::client_.

Referenced by smacc2::client_behaviors::CbWaitActionServer2< ActionT >::onEntry().

Here is the caller graph for this function:

◆ isServerReady()

template<typename ActionType >
bool smacc2::client_core_components::CpActionClient< ActionType >::isServerReady ( ) const
inline

Definition at line 141 of file cp_action_client.hpp.

141{ return client_ && client_->action_server_is_ready(); }

References smacc2::client_core_components::CpActionClient< ActionType >::client_.

◆ onAborted()

template<typename ActionType >
template<typename T >
boost::signals2::connection smacc2::client_core_components::CpActionClient< ActionType >::onAborted ( void(T::* callback )(const WrappedResult &),
T * object )
inline

Definition at line 208 of file cp_action_client.hpp.

209 {
210 return this->getStateMachine()->createSignalConnection(onActionAborted_, callback, object);
211 }
ISmaccStateMachine * getStateMachine()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
smacc2::SmaccSignal< void(const WrappedResult &)> onActionAborted_

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

Here is the call graph for this function:

◆ onCancelled()

template<typename ActionType >
template<typename T >
boost::signals2::connection smacc2::client_core_components::CpActionClient< ActionType >::onCancelled ( void(T::* callback )(const WrappedResult &),
T * object )
inline

Definition at line 214 of file cp_action_client.hpp.

215 {
216 return this->getStateMachine()->createSignalConnection(onActionCancelled_, callback, object);
217 }
smacc2::SmaccSignal< void(const WrappedResult &)> onActionCancelled_

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

Here is the call graph for this function:

◆ onComponentInitialization()

template<typename ActionType >
template<typename TOrthogonal , typename TSourceObject >
void smacc2::client_core_components::CpActionClient< ActionType >::onComponentInitialization ( )
inline

Definition at line 178 of file cp_action_client.hpp.

179 {
180 // Set up event posting functions with proper template parameters
181 postSuccessEvent = [this](const WrappedResult & result)
183
184 postAbortedEvent = [this](const WrappedResult & result)
186
187 postCancelledEvent = [this](const WrappedResult & result)
189
190 postFeedbackEvent = [this](const Feedback & feedback)
191 {
192 auto actionFeedbackEvent = new EvActionFeedback<Feedback, TOrthogonal>();
193 // actionFeedbackEvent->client = this->owner_;
194 actionFeedbackEvent->feedbackMessage = feedback;
195 this->postEvent(actionFeedbackEvent);
196 RCLCPP_DEBUG(getLogger(), "[%s] FEEDBACK EVENT", this->getName().c_str());
197 };
198 }
std::function< void(const WrappedResult &)> postCancelledEvent
typename GoalHandle::WrappedResult WrappedResult
std::function< void(const WrappedResult &)> postSuccessEvent
std::function< void(const WrappedResult &)> postAbortedEvent
std::function< void(const Feedback &)> postFeedbackEvent

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::client_core_components::CpActionClient< ActionType >::postAbortedEvent, smacc2::client_core_components::CpActionClient< ActionType >::postCancelledEvent, smacc2::ISmaccComponent::postEvent(), smacc2::client_core_components::CpActionClient< ActionType >::postFeedbackEvent, smacc2::client_core_components::CpActionClient< ActionType >::postResultEvent(), and smacc2::client_core_components::CpActionClient< ActionType >::postSuccessEvent.

Here is the call graph for this function:

◆ onFeedback() [1/2]

template<typename ActionType >
void smacc2::client_core_components::CpActionClient< ActionType >::onFeedback ( typename GoalHandle::SharedPtr ,
const std::shared_ptr< const Feedback > feedback_msg )
inlineprivate

◆ onFeedback() [2/2]

template<typename ActionType >
template<typename T >
boost::signals2::connection smacc2::client_core_components::CpActionClient< ActionType >::onFeedback ( void(T::* callback )(const Feedback &),
T * object )
inline

Definition at line 220 of file cp_action_client.hpp.

221 {
222 return this->getStateMachine()->createSignalConnection(onActionFeedback_, callback, object);
223 }

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

Referenced by smacc2::client_core_components::CpActionClient< ActionType >::onInitialize().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onInitialize()

template<typename ActionType >
void smacc2::client_core_components::CpActionClient< ActionType >::onInitialize ( )
inlineoverridevirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 155 of file cp_action_client.hpp.

156 {
157 if (!actionServerName)
158 {
159 RCLCPP_ERROR_STREAM(getLogger(), "[" << this->getName() << "] Action server name not set!");
160 return;
161 }
162
163 RCLCPP_INFO_STREAM(
164 getLogger(),
165 "[" << this->getName() << "] Initializing action client for: " << *actionServerName);
166
167 client_ = rclcpp_action::create_client<ActionType>(getNode(), *actionServerName);
168 RCLCPP_INFO_STREAM(
169 getLogger(),
170 "[" << this->getName() << "] DONE Initializing action client for: " << *actionServerName);
171
172 // Set up feedback callback
173 feedbackCallback_ = [this](auto goalHandle, auto feedback)
174 { this->onFeedback(goalHandle, feedback); };
175 }
rclcpp::Node::SharedPtr getNode()
boost::signals2::connection onFeedback(void(T::*callback)(const Feedback &), T *object)

References smacc2::client_core_components::CpActionClient< ActionType >::actionServerName, smacc2::client_core_components::CpActionClient< ActionType >::client_, smacc2::client_core_components::CpActionClient< ActionType >::feedbackCallback_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::ISmaccComponent::getNode(), and smacc2::client_core_components::CpActionClient< ActionType >::onFeedback().

Here is the call graph for this function:

◆ onResult()

template<typename ActionType >
void smacc2::client_core_components::CpActionClient< ActionType >::onResult ( const WrappedResult & result_msg)
inlineprivate

Definition at line 245 of file cp_action_client.hpp.

246 {
247 const auto & resultType = result_msg.code;
248
249 RCLCPP_INFO_STREAM(
250 getLogger(), "[" << this->getName() << "] Action result ["
251 << rclcpp_action::to_string(result_msg.goal_id) << "]: " << (int)resultType);
252
253 if (resultType == rclcpp_action::ResultCode::SUCCEEDED)
254 {
255 RCLCPP_INFO(getLogger(), "[%s] Action result: Success", this->getName().c_str());
256 onActionSucceeded_(result_msg);
257 postSuccessEvent(result_msg);
258 }
259 else if (resultType == rclcpp_action::ResultCode::ABORTED)
260 {
261 RCLCPP_INFO(getLogger(), "[%s] Action result: Aborted", this->getName().c_str());
262 onActionAborted_(result_msg);
263 postAbortedEvent(result_msg);
264 }
265 else if (resultType == rclcpp_action::ResultCode::CANCELED)
266 {
267 RCLCPP_INFO(getLogger(), "[%s] Action result: Cancelled", this->getName().c_str());
268 onActionCancelled_(result_msg);
269 postCancelledEvent(result_msg);
270 }
271 else
272 {
273 RCLCPP_WARN(
274 getLogger(), "[%s] Action result: Unhandled type: %d", this->getName().c_str(),
275 (int)resultType);
276 }
277 }
smacc2::SmaccSignal< void(const WrappedResult &)> onActionSucceeded_

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::client_core_components::CpActionClient< ActionType >::onActionAborted_, smacc2::client_core_components::CpActionClient< ActionType >::onActionCancelled_, smacc2::client_core_components::CpActionClient< ActionType >::onActionSucceeded_, smacc2::client_core_components::CpActionClient< ActionType >::postAbortedEvent, smacc2::client_core_components::CpActionClient< ActionType >::postCancelledEvent, and smacc2::client_core_components::CpActionClient< ActionType >::postSuccessEvent.

Referenced by smacc2::client_core_components::CpActionClient< ActionType >::sendGoal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onSucceeded()

template<typename ActionType >
template<typename T >
boost::signals2::connection smacc2::client_core_components::CpActionClient< ActionType >::onSucceeded ( void(T::* callback )(const WrappedResult &),
T * object )
inline

Definition at line 202 of file cp_action_client.hpp.

203 {
204 return this->getStateMachine()->createSignalConnection(onActionSucceeded_, callback, object);
205 }

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

Here is the call graph for this function:

◆ postResultEvent()

template<typename ActionType >
template<typename EvType >
void smacc2::client_core_components::CpActionClient< ActionType >::postResultEvent ( const WrappedResult & )
inlineprivate

Definition at line 280 of file cp_action_client.hpp.

281 {
282 auto * ev = new EvType();
283 RCLCPP_INFO(
284 getLogger(), "[%s] Posting event: %s", this->getName().c_str(),
285 smacc2::demangleSymbol(typeid(ev).name()).c_str());
286 this->postEvent(ev);
287 }
std::string demangleSymbol()

References smacc2::introspection::demangleSymbol(), smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), and smacc2::ISmaccComponent::postEvent().

Referenced by smacc2::client_core_components::CpActionClient< ActionType >::onComponentInitialization().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ sendGoal()

template<typename ActionType >
std::shared_future< typename GoalHandle::SharedPtr > smacc2::client_core_components::CpActionClient< ActionType >::sendGoal ( Goal & goal,
typename smacc2::SmaccSignal< void(const WrappedResult &)>::WeakPtr resultCallback = typename smacc2::SmaccSignal<void(const WrappedResult &)>::WeakPtr() )
inline

Definition at line 78 of file cp_action_client.hpp.

81 {
82 std::lock_guard<std::mutex> lock(actionMutex_);
83
84 SendGoalOptions options;
85
86 // Set up feedback callback
87 options.feedback_callback = feedbackCallback_;
88
89 // Set up result callback
90 options.result_callback = [this, resultCallback](const WrappedResult & result)
91 {
92 std::lock_guard<std::mutex> lock(actionMutex_);
93
94 RCLCPP_INFO_STREAM(
95 getLogger(), "[" << this->getName() << "] Action result callback, goal id: "
96 << rclcpp_action::to_string(result.goal_id));
97
98 auto resultCallbackPtr = resultCallback.lock();
99 if (resultCallbackPtr != nullptr)
100 {
101 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] Calling user result callback");
102 (*resultCallbackPtr)(result);
103 }
104 else
105 {
106 RCLCPP_INFO_STREAM(
107 getLogger(), "[" << this->getName() << "] Using default result handling");
108 this->onResult(result);
109 }
110 };
111
112 RCLCPP_INFO_STREAM(
113 getLogger(),
114 "[" << this->getName() << "] Sending goal to action server: " << (long)client_.get());
115
116 auto goalFuture = client_->async_send_goal(goal, options);
117 lastRequest_ = goalFuture;
118
119 return goalFuture;
120 }
typename ActionClient::SendGoalOptions SendGoalOptions
void onResult(const WrappedResult &result_msg)

References smacc2::client_core_components::CpActionClient< ActionType >::actionMutex_, smacc2::client_core_components::CpActionClient< ActionType >::client_, smacc2::client_core_components::CpActionClient< ActionType >::feedbackCallback_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::client_core_components::CpActionClient< ActionType >::lastRequest_, and smacc2::client_core_components::CpActionClient< ActionType >::onResult().

Here is the call graph for this function:

◆ waitForServer()

template<typename ActionType >
void smacc2::client_core_components::CpActionClient< ActionType >::waitForServer ( )
inline

Definition at line 143 of file cp_action_client.hpp.

144 {
145 if (client_)
146 {
147 RCLCPP_INFO_STREAM(
148 getLogger(),
149 "[" << this->getName() << "] Waiting for action server: " << *actionServerName);
150 client_->wait_for_action_server();
151 }
152 }

References smacc2::client_core_components::CpActionClient< ActionType >::client_, smacc2::ISmaccComponent::getLogger(), and smacc2::ISmaccComponent::getName().

Here is the call graph for this function:

Member Data Documentation

◆ actionMutex_

◆ actionServerName

template<typename ActionType >
std::optional<std::string> smacc2::client_core_components::CpActionClient< ActionType >::actionServerName

◆ client_

◆ feedbackCallback_

◆ lastCancelResponse_

template<typename ActionType >
std::optional< std::shared_future<typename rclcpp_action::Client<ActionType>::CancelResponse::SharedPtr> > smacc2::client_core_components::CpActionClient< ActionType >::lastCancelResponse_
private

◆ lastRequest_

template<typename ActionType >
std::optional<std::shared_future<typename GoalHandle::SharedPtr> > smacc2::client_core_components::CpActionClient< ActionType >::lastRequest_
private

◆ onActionAborted_

template<typename ActionType >
smacc2::SmaccSignal<void(const WrappedResult &)> smacc2::client_core_components::CpActionClient< ActionType >::onActionAborted_

◆ onActionCancelled_

template<typename ActionType >
smacc2::SmaccSignal<void(const WrappedResult &)> smacc2::client_core_components::CpActionClient< ActionType >::onActionCancelled_

◆ onActionFeedback_

template<typename ActionType >
smacc2::SmaccSignal<void(const Feedback &)> smacc2::client_core_components::CpActionClient< ActionType >::onActionFeedback_

◆ onActionSucceeded_

template<typename ActionType >
smacc2::SmaccSignal<void(const WrappedResult &)> smacc2::client_core_components::CpActionClient< ActionType >::onActionSucceeded_

◆ onGoalAccepted_

template<typename ActionType >
smacc2::SmaccSignal<void()> smacc2::client_core_components::CpActionClient< ActionType >::onGoalAccepted_

Definition at line 61 of file cp_action_client.hpp.

◆ onGoalRejected_

template<typename ActionType >
smacc2::SmaccSignal<void()> smacc2::client_core_components::CpActionClient< ActionType >::onGoalRejected_

Definition at line 62 of file cp_action_client.hpp.

◆ postAbortedEvent

◆ postCancelledEvent

◆ postFeedbackEvent

◆ postSuccessEvent

◆ serverTimeout

template<typename ActionType >
std::optional<std::chrono::milliseconds> smacc2::client_core_components::CpActionClient< ActionType >::serverTimeout

Definition at line 54 of file cp_action_client.hpp.


The documentation for this class was generated from the following file: