28#include <geometry_msgs/msg/pose.hpp>
58 template <
typename TOrthogonal,
typename TSourceObject>
66 std::optional<std::shared_future<
67 std::shared_ptr<rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose> > > >
68 sendNextGoal(std::optional<NavigateNextWaypointOptions> options = std::nullopt);
void initialize(ClNav2Z *client)
WaypointEventDispatcher waypointsEventDispatcher
void onGoalReached(const components::CpNav2ActionInterface::WrappedResult &res)
void onGoalAborted(const components::CpNav2ActionInterface::WrappedResult &)
boost::signals2::connection succeddedNav2ZClientConnection_
boost::signals2::connection abortedNav2ZClientConnection_
components::CpNav2ActionInterface * nav2ActionInterface_
smacc2::SmaccSignal< void()> onNavigationRequestCancelled
boost::signals2::connection cancelledNav2ZClientConnection_
void onInitialize() override
void onNavigationResult(const components::CpNav2ActionInterface::WrappedResult &r)
void onGoalCancelled(const components::CpNav2ActionInterface::WrappedResult &)
std::optional< std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > > sendNextGoal(std::optional< NavigateNextWaypointOptions > options=std::nullopt)
smacc2::SmaccSignal< void()> onNavigationRequestAborted
smacc2::SmaccSignal< void()> onNavigationRequestSucceded
void onStateOrthogonalAllocation()
typename GoalHandle::WrappedResult WrappedResult
void requiresComponent(TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
namespace cl_nav2z class ClNav2Z
std::optional< std::string > controllerName_
std::optional< std::string > goalCheckerName_