33 template <
typename TOrthogonal,
typename TSourceObject>
37 smacc2::SmaccAsyncClientBehavior::onOrthogonalAllocation<TOrthogonal, TSourceObject>();
57 std::shared_ptr<rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose> > >
void sendGoal(ClNav2Z::Goal &goal)
virtual void onNavigationResult(const ClNav2Z::WrappedResult &)
void onOrthogonalAllocation()
std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > goalHandleFuture_
bool isOwnActionResponse(const ClNav2Z::WrappedResult &)
cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::SharedPtr navigationCallback_
cl_nav2z::ClNav2Z * nav2zClient_
virtual void onNavigationActionSuccess(const ClNav2Z::WrappedResult &)
virtual void onNavigationActionAbort(const ClNav2Z::WrappedResult &)
rclcpp_action::ResultCode navigationResult_
virtual ~CbNav2ZClientBehaviorBase()
void requiresClient(SmaccClientType *&storage)
std::shared_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 > > SharedPtr
typename ActionClient::Goal Goal
GoalHandle::WrappedResult WrappedResult