|
SMACC2
|
#include <cb_navigate_backwards.hpp>


Public Member Functions | |
| CbNavigateBackwards (float backwardDistanceMeters) | |
| void | onEntry () override |
| void | onExit () override |
| CbNavigateBackwards (float backwardDistanceMeters) | |
| void | onEntry () override |
| void | onExit () override |
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 | backwardDistance |
| std::optional< float > | backwardSpeed |
| std::optional< std::string > | goalChecker_ |
| cl_nav2z::odom_tracker::CpOdomTracker * | odomTracker_ |
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 32 of file cb_navigate_backwards.hpp.
| cl_nav2z::CbNavigateBackwards::CbNavigateBackwards | ( | float | backwardDistanceMeters | ) |
Definition at line 35 of file cb_navigate_backward.cpp.
References backwardDistance, and smacc2::ISmaccClientBehavior::getLogger().

| cl_nav2z::CbNavigateBackwards::CbNavigateBackwards | ( | float | backwardDistanceMeters | ) |
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 45 of file cb_navigate_backward.cpp.
References backwardDistance, cl_nav2z::odom_tracker::CpOdomTracker::clearPath(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getNode(), cl_nav2z::CpPose::getReferenceFrame(), odomTracker_, smacc2::ISmaccClientBehavior::requiresComponent(), cl_nav2z::CbNav2ZClientBehaviorBase::sendGoal(), cl_nav2z::CpPlannerSwitcher::setBackwardPlanner(), cl_nav2z::CpGoalCheckerSwitcher::setGoalCheckerId(), cl_nav2z::odom_tracker::CpOdomTracker::setStartPoint(), cl_nav2z::odom_tracker::CpOdomTracker::setWorkingMode(), and cl_nav2z::CpPose::toPoseMsg().

|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 99 of file cb_navigate_backward.cpp.
References odomTracker_, and cl_nav2z::odom_tracker::CpOdomTracker::setWorkingMode().

|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
| float cl_nav2z::CbNavigateBackwards::backwardDistance |
Definition at line 35 of file cb_navigate_backwards.hpp.
Referenced by CbNavigateBackwards(), and onEntry().
| std::optional< float > cl_nav2z::CbNavigateBackwards::backwardSpeed |
Definition at line 38 of file cb_navigate_backwards.hpp.
| std::optional< std::string > cl_nav2z::CbNavigateBackwards::goalChecker_ |
Definition at line 40 of file cb_navigate_backwards.hpp.
| cl_nav2z::odom_tracker::CpOdomTracker * cl_nav2z::CbNavigateBackwards::odomTracker_ |
Definition at line 42 of file cb_navigate_backwards.hpp.