SMACC
|
#include <cb_navigate_global_position.h>
Public Member Functions | |
CbNavigateGlobalPosition () | |
CbNavigateGlobalPosition (float x, float y, float yaw) | |
void | setGoal (const geometry_msgs::Pose &pose) |
virtual void | onEntry () |
void | execute () |
void | readStartPoseFromParameterServer (ClMoveBaseZ::Goal &goal) |
virtual void | onExit () override |
Public Member Functions inherited from cl_move_base_z::CbMoveBaseClientBehaviorBase | |
template<typename TOrthogonal , typename TSourceObject > | |
void | onOrthogonalAllocation () |
Public Member Functions inherited from smacc::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 smacc::ISmaccClientBehavior | |
ISmaccClientBehavior () | |
virtual | ~ISmaccClientBehavior () |
ISmaccStateMachine * | getStateMachine () |
std::string | getName () const |
template<typename SmaccClientType > | |
void | requiresClient (SmaccClientType *&storage) |
template<typename SmaccComponentType > | |
void | requiresComponent (SmaccComponentType *&storage) |
ros::NodeHandle | getNode () |
Public Attributes | |
boost::optional< geometry_msgs::Point > | goalPosition |
boost::optional< float > | goalYaw |
Additional Inherited Members | |
Protected Member Functions inherited from smacc::SmaccAsyncClientBehavior | |
virtual void | executeOnEntry () override |
virtual void | executeOnExit () override |
void | postSuccessEvent () |
void | postFailureEvent () |
virtual void | dispose () override |
Protected Member Functions inherited from smacc::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 | executeOnEntry () |
virtual void | executeOnExit () |
virtual void | dispose () |
Protected Attributes inherited from cl_move_base_z::CbMoveBaseClientBehaviorBase | |
ClMoveBaseZ * | moveBaseClient_ |
ros::Publisher | visualizationMarkersPub_ |
Definition at line 14 of file cb_navigate_global_position.h.
cl_move_base_z::CbNavigateGlobalPosition::CbNavigateGlobalPosition | ( | ) |
Definition at line 10 of file cb_navigate_global_position.cpp.
cl_move_base_z::CbNavigateGlobalPosition::CbNavigateGlobalPosition | ( | float | x, |
float | y, | ||
float | yaw | ||
) |
Definition at line 14 of file cb_navigate_global_position.cpp.
References goalPosition, and goalYaw.
void cl_move_base_z::CbNavigateGlobalPosition::execute | ( | ) |
Definition at line 47 of file cb_navigate_global_position.cpp.
References smacc::ISmaccClient::getComponent(), cl_move_base_z::Pose::getReferenceFrame(), smacc::ISmaccClientBehavior::getStateMachine(), cl_move_base_z::CbMoveBaseClientBehaviorBase::moveBaseClient_, readStartPoseFromParameterServer(), smacc::client_bases::SmaccActionClientBase< ActionType >::sendGoal(), and smacc::ISmaccStateMachine::setGlobalSMData().
Referenced by onEntry().
|
virtual |
Reimplemented from smacc::ISmaccClientBehavior.
Definition at line 29 of file cb_navigate_global_position.cpp.
References execute(), smacc::ISmaccClient::getComponent(), cl_move_base_z::CbMoveBaseClientBehaviorBase::moveBaseClient_, and cl_move_base_z::PlannerSwitcher::setDefaultPlanners().
|
overridevirtual |
Reimplemented from smacc::ISmaccClientBehavior.
Definition at line 88 of file cb_navigate_global_position.cpp.
void cl_move_base_z::CbNavigateGlobalPosition::readStartPoseFromParameterServer | ( | ClMoveBaseZ::Goal & | goal | ) |
Definition at line 66 of file cb_navigate_global_position.cpp.
References smacc::ISmaccClientBehavior::getCurrentState(), smacc::ISmaccState::getParam(), goalPosition, and goalYaw.
Referenced by execute().
void cl_move_base_z::CbNavigateGlobalPosition::setGoal | ( | const geometry_msgs::Pose & | pose | ) |
Definition at line 23 of file cb_navigate_global_position.cpp.
References goalPosition, and goalYaw.
boost::optional<geometry_msgs::Point> cl_move_base_z::CbNavigateGlobalPosition::goalPosition |
Definition at line 17 of file cb_navigate_global_position.h.
Referenced by CbNavigateGlobalPosition(), readStartPoseFromParameterServer(), and setGoal().
boost::optional<float> cl_move_base_z::CbNavigateGlobalPosition::goalYaw |
Definition at line 18 of file cb_navigate_global_position.h.
Referenced by CbNavigateGlobalPosition(), readStartPoseFromParameterServer(), and setGoal().