36 template <
typename TOrthogonal,
typename TSourceObject>
48 void sendGoal(nav2_msgs::action::NavigateToPose::Goal & goal)
73 return boost::signals2::connection();
84 return boost::signals2::connection();
95 return boost::signals2::connection();
virtual void onNavigationActionSuccess(const components::CpNav2ActionInterface::WrappedResult &)
smacc2::client_core_components::CpActionClient< nav2_msgs::action::NavigateToPose > * actionClient_
components::CpNav2ActionInterface * nav2ActionInterface_
virtual void onNavigationActionAbort(const components::CpNav2ActionInterface::WrappedResult &)
boost::signals2::connection onNavigationSucceeded(void(T::*callback)(const components::CpNav2ActionInterface::WrappedResult &), T *object)
virtual void onNavigationResult(const components::CpNav2ActionInterface::WrappedResult &)
void sendGoal(nav2_msgs::action::NavigateToPose::Goal &goal)
boost::signals2::connection onNavigationAborted(void(T::*callback)(const components::CpNav2ActionInterface::WrappedResult &), T *object)
void onStateOrthogonalAllocation()
rclcpp_action::ResultCode navigationResult_
boost::signals2::connection onNavigationCancelled(void(T::*callback)(const components::CpNav2ActionInterface::WrappedResult &), T *object)
virtual ~CbNav2ZClientBehaviorBase()
boost::signals2::connection onNavigationCancelled(void(T::*callback)(const WrappedResult &), T *object)
boost::signals2::connection onNavigationSucceeded(void(T::*callback)(const WrappedResult &), T *object)
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)
typename GoalHandle::WrappedResult WrappedResult
boost::signals2::connection onNavigationAborted(void(T::*callback)(const WrappedResult &), T *object)
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
void onStateOrthogonalAllocation()