SMACC2
|
#include <cb_navigate_forward.hpp>
Public Member Functions | |
CbNavigateForward () | |
CbNavigateForward (float forwardDistance) | |
CbNavigateForward (geometry_msgs::msg::PoseStamped goalPosition) | |
virtual | ~CbNavigateForward () |
void | onEntry () override |
void | onExit () override |
void | setForwardDistance (float distance_meters) |
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 | |
std::optional< float > | forwardSpeed |
std::optional< geometry_msgs::msg::Quaternion > | forceInitialOrientation |
std::optional< std::string > | goalChecker_ |
Protected Attributes | |
odom_tracker::OdomTracker * | odomTracker_ |
std::optional< geometry_msgs::msg::PoseStamped > | goalPose_ |
std::optional< float > | forwardDistance_ |
Protected Attributes inherited from cl_nav2z::CbNav2ZClientBehaviorBase | |
cl_nav2z::ClNav2Z * | moveBaseClient_ |
rclcpp_action::ResultCode | navigationResult_ |
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 () |
Definition at line 34 of file cb_navigate_forward.hpp.
cl_nav2z::CbNavigateForward::CbNavigateForward | ( | ) |
Definition at line 36 of file cb_navigate_forward.cpp.
cl_nav2z::CbNavigateForward::CbNavigateForward | ( | float | forwardDistance | ) |
Definition at line 35 of file cb_navigate_forward.cpp.
cl_nav2z::CbNavigateForward::CbNavigateForward | ( | geometry_msgs::msg::PoseStamped | goalPosition | ) |
Definition at line 38 of file cb_navigate_forward.cpp.
|
virtual |
Definition at line 40 of file cb_navigate_forward.cpp.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 57 of file cb_navigate_forward.cpp.
References forceInitialOrientation, forwardDistance_, smacc2::ISmaccClient::getComponent(), smacc2::ISmaccClientBehavior::getCurrentState(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccState::getName(), smacc2::ISmaccClientBehavior::getNode(), cl_nav2z::Pose::getReferenceFrame(), goalPose_, cl_nav2z::CbNav2ZClientBehaviorBase::moveBaseClient_, odomTracker_, cl_nav2z::odom_tracker::OdomTracker::pushPath(), smacc2::client_bases::SmaccActionClientBase< ActionType >::sendGoal(), cl_nav2z::odom_tracker::OdomTracker::setCurrentMotionGoal(), setForwardDistance(), cl_nav2z::PlannerSwitcher::setForwardPlanner(), cl_nav2z::GoalCheckerSwitcher::setGoalCheckerId(), cl_nav2z::odom_tracker::OdomTracker::setStartPoint(), and cl_nav2z::odom_tracker::OdomTracker::setWorkingMode().
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 147 of file cb_navigate_forward.cpp.
References odomTracker_, and cl_nav2z::odom_tracker::OdomTracker::setWorkingMode().
void cl_nav2z::CbNavigateForward::setForwardDistance | ( | float | distance_meters | ) |
Definition at line 42 of file cb_navigate_forward.cpp.
References forwardDistance_, smacc2::ISmaccClientBehavior::getLogger(), and smacc2::ISmaccClientBehavior::getName().
Referenced by onEntry(), and sm_dance_bot_strikes_back::radial_motion_states::StiRadialEndPoint::runtimeConfigure().
std::optional<geometry_msgs::msg::Quaternion> cl_nav2z::CbNavigateForward::forceInitialOrientation |
Definition at line 43 of file cb_navigate_forward.hpp.
Referenced by onEntry().
|
protected |
Definition at line 72 of file cb_navigate_forward.hpp.
Referenced by onEntry(), and setForwardDistance().
std::optional<float> cl_nav2z::CbNavigateForward::forwardSpeed |
Definition at line 38 of file cb_navigate_forward.hpp.
std::optional<std::string> cl_nav2z::CbNavigateForward::goalChecker_ |
Definition at line 46 of file cb_navigate_forward.hpp.
|
protected |
Definition at line 70 of file cb_navigate_forward.hpp.
Referenced by onEntry().
|
protected |
Definition at line 68 of file cb_navigate_forward.hpp.