|
SMACC2
|
#include <cb_absolute_rotate.hpp>


Public Member Functions | |
| CbAbsoluteRotate () | |
| CbAbsoluteRotate (float absoluteGoalAngleDegree, float yawGoalTolerance=-1) | |
| void | onEntry () override |
| void | onExit () override |
Public Member Functions inherited from cl_nav2z::CbNav2ZClientBehaviorBase | |
| virtual | ~CbNav2ZClientBehaviorBase () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior | |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| 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=false) |
| virtual void | onEntry () |
| virtual void | onExit () |
| virtual void | executeOnEntry () |
| virtual void | executeOnExit () |
Public Attributes | |
| std::shared_ptr< tf2_ros::Buffer > | listener |
| float | absoluteGoalAngleDegree |
| std::optional< float > | yawGoalTolerance |
| std::optional< float > | maxVelTheta |
| std::optional< SpinningPlanner > | spinningPlanner |
Private Member Functions | |
| void | updateTemporalBehaviorParameters (bool undo) |
Private Attributes | |
| float | oldYawTolerance |
| float | oldMaxVelTheta |
| float | oldMinVelTheta |
Additional Inherited Members | |
Protected Member Functions inherited from cl_nav2z::CbNav2ZClientBehaviorBase | |
| 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 () |
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 void | dispose () |
| virtual rclcpp::Node::SharedPtr | getNode () const |
| virtual rclcpp::Logger | getLogger () const |
Protected Attributes inherited from cl_nav2z::CbNav2ZClientBehaviorBase | |
| cl_nav2z::ClNav2Z * | nav2zClient_ |
| cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::SharedPtr | navigationCallback_ |
| rclcpp_action::ResultCode | navigationResult_ |
| std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > | goalHandleFuture_ |
Definition at line 29 of file cb_absolute_rotate.hpp.
| cl_nav2z::CbAbsoluteRotate::CbAbsoluteRotate | ( | ) |
Definition at line 32 of file cb_absolute_rotate.cpp.
| cl_nav2z::CbAbsoluteRotate::CbAbsoluteRotate | ( | float | absoluteGoalAngleDegree, |
| float | yawGoalTolerance = -1 |
||
| ) |
Definition at line 33 of file cb_absolute_rotate.cpp.
References absoluteGoalAngleDegree, and yawGoalTolerance.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Reimplemented in cl_nav2z::CbRotateLookAt.
Definition at line 43 of file cb_absolute_rotate.cpp.
References absoluteGoalAngleDegree, smacc2::ISmaccClient::getComponent(), smacc2::ISmaccClientBehavior::getCurrentState(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccState::getName(), smacc2::ISmaccClientBehavior::getNode(), cl_nav2z::Pose::getReferenceFrame(), listener, cl_nav2z::CbNav2ZClientBehaviorBase::nav2zClient_, cl_nav2z::PureSpinning, cl_nav2z::odom_tracker::RECORD_PATH, cl_nav2z::CbNav2ZClientBehaviorBase::sendGoal(), cl_nav2z::GoalCheckerSwitcher::setGoalCheckerId(), cl_nav2z::PlannerSwitcher::setPureSpinningPlanner(), spinningPlanner, and updateTemporalBehaviorParameters().
Referenced by cl_nav2z::CbRotateLookAt::onEntry().


|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 257 of file cb_absolute_rotate.cpp.
References cl_nav2z::PureSpinning, spinningPlanner, and updateTemporalBehaviorParameters().

|
private |
Definition at line 100 of file cb_absolute_rotate.cpp.
References cl_nav2z::Default, smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccClientBehavior::getNode(), maxVelTheta, oldMaxVelTheta, oldMinVelTheta, oldYawTolerance, cl_nav2z::PureSpinning, spinningPlanner, and yawGoalTolerance.
Referenced by onEntry(), and onExit().


| float cl_nav2z::CbAbsoluteRotate::absoluteGoalAngleDegree |
Definition at line 34 of file cb_absolute_rotate.hpp.
Referenced by CbAbsoluteRotate(), onEntry(), and cl_nav2z::CbRotateLookAt::onEntry().
| std::shared_ptr<tf2_ros::Buffer> cl_nav2z::CbAbsoluteRotate::listener |
Definition at line 32 of file cb_absolute_rotate.hpp.
Referenced by onEntry().
| std::optional<float> cl_nav2z::CbAbsoluteRotate::maxVelTheta |
Definition at line 36 of file cb_absolute_rotate.hpp.
Referenced by updateTemporalBehaviorParameters().
|
private |
Definition at line 48 of file cb_absolute_rotate.hpp.
Referenced by updateTemporalBehaviorParameters().
|
private |
Definition at line 49 of file cb_absolute_rotate.hpp.
Referenced by updateTemporalBehaviorParameters().
|
private |
Definition at line 47 of file cb_absolute_rotate.hpp.
Referenced by updateTemporalBehaviorParameters().
| std::optional<SpinningPlanner> cl_nav2z::CbAbsoluteRotate::spinningPlanner |
Definition at line 37 of file cb_absolute_rotate.hpp.
Referenced by onEntry(), onExit(), and updateTemporalBehaviorParameters().
| std::optional<float> cl_nav2z::CbAbsoluteRotate::yawGoalTolerance |
Definition at line 35 of file cb_absolute_rotate.hpp.
Referenced by CbAbsoluteRotate(), and updateTemporalBehaviorParameters().