SMACC2
|
#include <cb_rotate.hpp>
Public Member Functions | |
CbRotate (float rotate_degree) | |
CbRotate (float rotate_degree, cl_nav2z::SpinningPlanner spinning_planner) | |
void | onEntry () 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) |
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) |
Public Attributes | |
float | rotateDegree |
std::optional< std::string > | goalChecker_ |
std::optional< cl_nav2z::SpinningPlanner > | spinningPlanner |
Private Attributes | |
std::shared_ptr< tf2_ros::Buffer > | listener |
Additional Inherited Members | |
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 () |
virtual void | onEntry () |
virtual void | onExit () |
template<typename EventType > | |
void | postEvent (const EventType &ev) |
template<typename EventType > | |
void | postEvent () |
ISmaccState * | getCurrentState () |
virtual void | dispose () |
virtual rclcpp::Node::SharedPtr | getNode () |
virtual rclcpp::Logger | getLogger () |
Protected Attributes inherited from cl_nav2z::CbNav2ZClientBehaviorBase | |
cl_nav2z::ClNav2Z * | moveBaseClient_ |
rclcpp_action::ResultCode | navigationResult_ |
Definition at line 28 of file cb_rotate.hpp.
cl_nav2z::CbRotate::CbRotate | ( | float | rotate_degree | ) |
Definition at line 29 of file cb_rotate.cpp.
cl_nav2z::CbRotate::CbRotate | ( | float | rotate_degree, |
cl_nav2z::SpinningPlanner | spinning_planner | ||
) |
Definition at line 31 of file cb_rotate.cpp.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 36 of file cb_rotate.cpp.
References smacc2::ISmaccClient::getComponent(), smacc2::ISmaccClientBehavior::getCurrentState(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccState::getName(), smacc2::ISmaccClientBehavior::getNode(), cl_nav2z::Pose::getReferenceFrame(), cl_nav2z::CbNav2ZClientBehaviorBase::moveBaseClient_, cl_nav2z::PureSpinning, cl_nav2z::odom_tracker::RECORD_PATH, smacc2::ISmaccClientBehavior::requiresClient(), rotateDegree, smacc2::client_bases::SmaccActionClientBase< ActionType >::sendGoal(), cl_nav2z::PlannerSwitcher::setPureSpinningPlanner(), and spinningPlanner.
std::optional<std::string> cl_nav2z::CbRotate::goalChecker_ |
Definition at line 33 of file cb_rotate.hpp.
|
private |
Definition at line 45 of file cb_rotate.hpp.
float cl_nav2z::CbRotate::rotateDegree |
Definition at line 31 of file cb_rotate.hpp.
Referenced by onEntry().
std::optional<cl_nav2z::SpinningPlanner> cl_nav2z::CbRotate::spinningPlanner |
Definition at line 35 of file cb_rotate.hpp.
Referenced by onEntry().