SMACC
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | List of all members
cl_move_base_z::CbNavigateGlobalPosition Class Reference

#include <cb_navigate_global_position.h>

Inheritance diagram for cl_move_base_z::CbNavigateGlobalPosition:
Inheritance graph
Collaboration diagram for cl_move_base_z::CbNavigateGlobalPosition:
Collaboration graph

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 ()
 
ISmaccStateMachinegetStateMachine ()
 
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 ()
 
ISmaccStategetCurrentState ()
 
virtual void executeOnEntry ()
 
virtual void executeOnExit ()
 
virtual void dispose ()
 
- Protected Attributes inherited from cl_move_base_z::CbMoveBaseClientBehaviorBase
ClMoveBaseZmoveBaseClient_
 
ros::Publisher visualizationMarkersPub_
 

Detailed Description

Definition at line 14 of file cb_navigate_global_position.h.

Constructor & Destructor Documentation

◆ CbNavigateGlobalPosition() [1/2]

cl_move_base_z::CbNavigateGlobalPosition::CbNavigateGlobalPosition ( )

Definition at line 10 of file cb_navigate_global_position.cpp.

11{
12}

◆ CbNavigateGlobalPosition() [2/2]

cl_move_base_z::CbNavigateGlobalPosition::CbNavigateGlobalPosition ( float  x,
float  y,
float  yaw 
)

Definition at line 14 of file cb_navigate_global_position.cpp.

15{
16 auto p = geometry_msgs::Point();
17 p.x = x;
18 p.y = y;
19 goalPosition = p;
20 goalYaw = yaw;
21}
boost::optional< geometry_msgs::Point > goalPosition

References goalPosition, and goalYaw.

Member Function Documentation

◆ execute()

void cl_move_base_z::CbNavigateGlobalPosition::execute ( )

Definition at line 47 of file cb_navigate_global_position.cpp.

48{
50 auto referenceFrame = p->getReferenceFrame();
51 auto currentPoseMsg = p->toPoseMsg();
52
53 ROS_INFO("Sending Goal to MoveBase");
54 ClMoveBaseZ::Goal goal;
55 goal.target_pose.header.frame_id = referenceFrame;
56 goal.target_pose.header.stamp = ros::Time::now();
58
59 // store the start pose on the state machine storage so that it can
60 // be referenced from other states (for example return to radial start)
61 this->getStateMachine()->setGlobalSMData("radial_start_pose", goal.target_pose);
62
64}
void readStartPoseFromParameterServer(ClMoveBaseZ::Goal &goal)
const std::string & getReferenceFrame() const
Definition: cp_pose.h:39
ISmaccStateMachine * getStateMachine()
TComponent * getComponent()
void setGlobalSMData(std::string name, T value)

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onEntry()

void cl_move_base_z::CbNavigateGlobalPosition::onEntry ( )
virtual

Reimplemented from smacc::ISmaccClientBehavior.

Definition at line 29 of file cb_navigate_global_position.cpp.

30{
31 ROS_INFO("[CbNavigateGlobalPosition] Entering Navigate Global position");
32
33 auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();
34 plannerSwitcher->setDefaultPlanners();
35
36 auto pose = moveBaseClient_->getComponent<cl_move_base_z::Pose>()->toPoseMsg();
37 auto *odomTracker = moveBaseClient_->getComponent<OdomTracker>();
38
39 odomTracker->pushPath("FreeNavigationToGoalPose");
40 odomTracker->setStartPoint(pose);
41 odomTracker->setWorkingMode(WorkingMode::RECORD_PATH);
42
43 execute();
44}

References execute(), smacc::ISmaccClient::getComponent(), cl_move_base_z::CbMoveBaseClientBehaviorBase::moveBaseClient_, and cl_move_base_z::PlannerSwitcher::setDefaultPlanners().

Here is the call graph for this function:

◆ onExit()

void cl_move_base_z::CbNavigateGlobalPosition::onExit ( )
overridevirtual

Reimplemented from smacc::ISmaccClientBehavior.

Definition at line 88 of file cb_navigate_global_position.cpp.

89{
90 ROS_INFO("Exiting move goal Action Client");
91}

◆ readStartPoseFromParameterServer()

void cl_move_base_z::CbNavigateGlobalPosition::readStartPoseFromParameterServer ( ClMoveBaseZ::Goal &  goal)

Definition at line 66 of file cb_navigate_global_position.cpp.

67{
68 if (!goalPosition)
69 {
70 this->getCurrentState()->getParam("start_position_x", goal.target_pose.pose.position.x);
71 this->getCurrentState()->getParam("start_position_y", goal.target_pose.pose.position.y);
72 double yaw;
73 this->getCurrentState()->getParam("start_position_yaw", yaw);
74
75 goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
76 }
77 else
78 {
79 goal.target_pose.pose.position = *goalPosition;
80 goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(*goalYaw);
81 }
82
83 ROS_INFO_STREAM("start position read from parameter server: " << goal.target_pose.pose.position);
84}
bool getParam(std::string param_name, T &param_storage)

References smacc::ISmaccClientBehavior::getCurrentState(), smacc::ISmaccState::getParam(), goalPosition, and goalYaw.

Referenced by execute().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setGoal()

void cl_move_base_z::CbNavigateGlobalPosition::setGoal ( const geometry_msgs::Pose &  pose)

Definition at line 23 of file cb_navigate_global_position.cpp.

24{
25 goalPosition = pose.position;
26 goalYaw = tf::getYaw(pose.orientation);
27}

References goalPosition, and goalYaw.

Member Data Documentation

◆ goalPosition

boost::optional<geometry_msgs::Point> cl_move_base_z::CbNavigateGlobalPosition::goalPosition

◆ goalYaw

boost::optional<float> cl_move_base_z::CbNavigateGlobalPosition::goalYaw

The documentation for this class was generated from the following files: