Class CpNav2ActionInterface

Inheritance Relationships

Base Type

  • public smacc2::ISmaccComponent

Class Documentation

class CpNav2ActionInterface : public smacc2::ISmaccComponent

Public Types

using ActionType = nav2_msgs::action::NavigateToPose
using Goal = ActionType::Goal
using Result = ActionType::Result
using Feedback = ActionType::Feedback
using GoalHandle = rclcpp_action::ClientGoalHandle<ActionType>
using WrappedResult = typename GoalHandle::WrappedResult
using ActionClient = smacc2::client_core_components::CpActionClient<ActionType>

Public Functions

CpNav2ActionInterface() = default
virtual ~CpNav2ActionInterface() = default
inline std::shared_future<typename GoalHandle::SharedPtr> sendNavigationGoal(const geometry_msgs::msg::PoseStamped &target)
inline std::shared_future<typename GoalHandle::SharedPtr> sendGoal(Goal &goal)
inline bool cancelNavigation()
inline bool isNavigationServerReady() const
inline void waitForNavigationServer()
template<typename TOrthogonal, typename TClient>
inline void onComponentInitialization()
inline void onInitialize() override
inline ActionClient *getActionClient() const
template<typename T>
inline boost::signals2::connection onNavigationSucceeded(void (T::* callback)(const WrappedResult&), T *object)
template<typename T>
inline boost::signals2::connection onNavigationAborted(void (T::* callback)(const WrappedResult&), T *object)
template<typename T>
inline boost::signals2::connection onNavigationCancelled(void (T::* callback)(const WrappedResult&), T *object)
template<typename T>
inline boost::signals2::connection onNavigationFeedback(void (T::* callback)(const Feedback&), T *object)

Public Members

smacc2::SmaccSignal<void(const WrappedResult&)> onNavigationSucceeded_
smacc2::SmaccSignal<void(const WrappedResult&)> onNavigationAborted_
smacc2::SmaccSignal<void(const WrappedResult&)> onNavigationCancelled_
smacc2::SmaccSignal<void(const Feedback&)> onNavigationFeedback_
std::function<void(const WrappedResult&)> postNavigationSuccessEvent
std::function<void(const WrappedResult&)> postNavigationAbortedEvent
std::function<void(const WrappedResult&)> postNavigationCancelledEvent
std::function<void(const Feedback&)> postNavigationFeedbackEvent