|
SMACC2
|
#include <cb_navigate_global_position.hpp>


Public Member Functions | |
| CbNavigateGlobalPosition () | |
| CbNavigateGlobalPosition (float x, float y, float yaw, std::optional< CbNavigateGlobalPositionOptions > options=std::nullopt) | |
| void | setGoal (const geometry_msgs::msg::Pose &pose) |
| virtual void | onEntry () override |
| void | onExit () override |
| void | execute () |
| CbNavigateGlobalPosition () | |
| CbNavigateGlobalPosition (float x, float y, float yaw, std::optional< CbNavigateGlobalPositionOptions > options=std::nullopt) | |
| void | setGoal (const geometry_msgs::msg::Pose &pose) |
| virtual void | onEntry () override |
| void | onExit () override |
| void | execute () |
Public Member Functions inherited from cl_nav2z::CbNav2ZClientBehaviorBase | |
| virtual | ~CbNav2ZClientBehaviorBase () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onStateOrthogonalAllocation () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| virtual | ~CbNav2ZClientBehaviorBase () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onStateOrthogonalAllocation () |
Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior | |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onStateOrthogonalAllocation () |
| virtual | ~SmaccAsyncClientBehavior () |
| template<typename TCallback , typename T > | |
| boost::signals2::connection | onSuccess (TCallback callback, T *object) |
| template<typename TCallback , typename T > | |
| boost::signals2::connection | onFinished (TCallback callback, T *object) |
| template<typename TCallback , typename T > | |
| boost::signals2::connection | onFailure (TCallback callback, T *object) |
| void | requestForceFinish () |
| void | executeOnEntry () override |
| void | executeOnExit () override |
| void | waitOnEntryThread (bool requestFinish) |
| template<typename TCallbackMethod , typename T > | |
| boost::signals2::connection | onSuccess (TCallbackMethod callback, T *object) |
| template<typename TCallbackMethod , typename T > | |
| boost::signals2::connection | onFinished (TCallbackMethod callback, T *object) |
| template<typename TCallbackMethod , typename T > | |
| boost::signals2::connection | onFailure (TCallbackMethod callback, T *object) |
Public Member Functions inherited from smacc2::ISmaccClientBehavior | |
| ISmaccClientBehavior () | |
| virtual | ~ISmaccClientBehavior () |
| ISmaccStateMachine * | getStateMachine () |
| std::string | getName () const |
| template<typename SmaccClientType > | |
| void | requiresClient (SmaccClientType *&storage) |
| template<typename SmaccComponentType > | |
| void | requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist) |
| template<typename SmaccComponentType > | |
| void | requiresComponent (SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
Public Attributes | |
| float | goalYaw |
| CbNavigateGlobalPositionOptions | options |
| geometry_msgs::msg::Point | goalPosition |
Private Member Functions | |
| void | readStartPoseFromParameterServer (nav2_msgs::action::NavigateToPose::Goal &goal) |
| void | readStartPoseFromParameterServer (ClNav2Z::Goal &goal) |
Additional Inherited Members | |
Protected Member Functions inherited from cl_nav2z::CbNav2ZClientBehaviorBase | |
| void | sendGoal (nav2_msgs::action::NavigateToPose::Goal &goal) |
| void | cancelGoal () |
| template<typename T > | |
| boost::signals2::connection | onNavigationSucceeded (void(T::*callback)(const components::CpNav2ActionInterface::WrappedResult &), T *object) |
| template<typename T > | |
| boost::signals2::connection | onNavigationAborted (void(T::*callback)(const components::CpNav2ActionInterface::WrappedResult &), T *object) |
| template<typename T > | |
| boost::signals2::connection | onNavigationCancelled (void(T::*callback)(const components::CpNav2ActionInterface::WrappedResult &), T *object) |
| virtual void | onNavigationResult (const components::CpNav2ActionInterface::WrappedResult &) |
| virtual void | onNavigationActionSuccess (const components::CpNav2ActionInterface::WrappedResult &) |
| virtual void | onNavigationActionAbort (const components::CpNav2ActionInterface::WrappedResult &) |
| void | sendGoal (ClNav2Z::Goal &goal) |
| void | cancelGoal () |
| bool | isOwnActionResponse (const ClNav2Z::WrappedResult &) |
| virtual void | onNavigationResult (const ClNav2Z::WrappedResult &) |
| virtual void | onNavigationActionSuccess (const ClNav2Z::WrappedResult &) |
| virtual void | onNavigationActionAbort (const ClNav2Z::WrappedResult &) |
Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior | |
| void | postSuccessEvent () |
| void | postFailureEvent () |
| virtual void | dispose () override |
| bool | isShutdownRequested () |
| onEntry is executed in a new thread. However the current state cannot be left until the onEntry thread finishes. This flag can be checked from the onEntry thread to force finishing the thread. | |
Protected Member Functions inherited from smacc2::ISmaccClientBehavior | |
| virtual void | runtimeConfigure () |
| template<typename EventType > | |
| void | postEvent (const EventType &ev) |
| template<typename EventType > | |
| void | postEvent () |
| ISmaccState * | getCurrentState () |
| virtual rclcpp::Node::SharedPtr | getNode () const |
| virtual rclcpp::Logger | getLogger () const |
Protected Attributes inherited from cl_nav2z::CbNav2ZClientBehaviorBase | |
| components::CpNav2ActionInterface * | nav2ActionInterface_ = nullptr |
| smacc2::client_core_components::CpActionClient< nav2_msgs::action::NavigateToPose > * | actionClient_ = nullptr |
| rclcpp_action::ResultCode | navigationResult_ |
| cl_nav2z::ClNav2Z * | nav2zClient_ |
| cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::SharedPtr | navigationCallback_ |
| std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > | goalHandleFuture_ |
Definition at line 40 of file cb_navigate_global_position.hpp.
| cl_nav2z::CbNavigateGlobalPosition::CbNavigateGlobalPosition | ( | ) |
Definition at line 33 of file cb_navigate_global_position.cpp.
| cl_nav2z::CbNavigateGlobalPosition::CbNavigateGlobalPosition | ( | float | x, |
| float | y, | ||
| float | yaw, | ||
| std::optional< CbNavigateGlobalPositionOptions > | options = std::nullopt ) |
Definition at line 35 of file cb_navigate_global_position.cpp.
References goalPosition, goalYaw, and options.
| cl_nav2z::CbNavigateGlobalPosition::CbNavigateGlobalPosition | ( | ) |
| cl_nav2z::CbNavigateGlobalPosition::CbNavigateGlobalPosition | ( | float | x, |
| float | y, | ||
| float | yaw, | ||
| std::optional< CbNavigateGlobalPositionOptions > | options = std::nullopt ) |
| void cl_nav2z::CbNavigateGlobalPosition::execute | ( | ) |
Definition at line 90 of file cb_navigate_global_position.cpp.
References smacc2::ISmaccClientBehavior::getLogger(), cl_nav2z::CpPose::getReferenceFrame(), goalPosition, goalYaw, smacc2::ISmaccClientBehavior::requiresComponent(), and cl_nav2z::CbNav2ZClientBehaviorBase::sendGoal().
Referenced by onEntry().


| void cl_nav2z::CbNavigateGlobalPosition::execute | ( | ) |
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Reimplemented in cl_nav2z::CbStopNavigation, and cl_nav2z::CbStopNavigation.
Definition at line 53 of file cb_navigate_global_position.cpp.
References cl_nav2z::CpPlannerSwitcher::commitPublish(), cl_nav2z::CbNavigateGlobalPositionOptions::controllerName_, execute(), smacc2::ISmaccClientBehavior::getCurrentState(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccState::getName(), options, cl_nav2z::odom_tracker::CpOdomTracker::pushPath(), smacc2::ISmaccClientBehavior::requiresComponent(), cl_nav2z::CpPlannerSwitcher::setDefaultPlanners(), cl_nav2z::CpPlannerSwitcher::setDesiredController(), cl_nav2z::CpGoalCheckerSwitcher::setGoalCheckerId(), cl_nav2z::odom_tracker::CpOdomTracker::setStartPoint(), cl_nav2z::odom_tracker::CpOdomTracker::setWorkingMode(), and cl_nav2z::CpPose::toPoseMsg().
Referenced by cl_nav2z::CbStopNavigation::onEntry().


|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Reimplemented in cl_nav2z::CbStopNavigation, and cl_nav2z::CbStopNavigation.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Reimplemented in cl_nav2z::CbStopNavigation, and cl_nav2z::CbStopNavigation.
Definition at line 113 of file cb_navigate_global_position.cpp.
References smacc2::ISmaccClientBehavior::getLogger().

|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Reimplemented in cl_nav2z::CbStopNavigation, and cl_nav2z::CbStopNavigation.
|
private |
|
private |
| void cl_nav2z::CbNavigateGlobalPosition::setGoal | ( | const geometry_msgs::msg::Pose & | pose | ) |
Definition at line 47 of file cb_navigate_global_position.cpp.
References goalPosition, and goalYaw.
Referenced by cl_nav2z::CbStopNavigation::onEntry().

| void cl_nav2z::CbNavigateGlobalPosition::setGoal | ( | const geometry_msgs::msg::Pose & | pose | ) |
| geometry_msgs::msg::Point cl_nav2z::CbNavigateGlobalPosition::goalPosition |
Definition at line 47 of file cb_navigate_global_position.hpp.
Referenced by CbNavigateGlobalPosition(), execute(), and setGoal().
| float cl_nav2z::CbNavigateGlobalPosition::goalYaw |
Definition at line 44 of file cb_navigate_global_position.hpp.
Referenced by CbNavigateGlobalPosition(), execute(), and setGoal().
| CbNavigateGlobalPositionOptions cl_nav2z::CbNavigateGlobalPosition::options |
Definition at line 46 of file cb_navigate_global_position.hpp.
Referenced by CbNavigateGlobalPosition(), and onEntry().