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

#include <cb_rotate.h>

Inheritance diagram for cl_move_base_z::CbRotate:
Inheritance graph
Collaboration diagram for cl_move_base_z::CbRotate:
Collaboration graph

Public Member Functions

 CbRotate ()
 
 CbRotate (float rotate_degree)
 
virtual void onEntry () 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

tf::TransformListener listener
 
boost::optional< float > rotateDegree
 

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 13 of file cb_rotate.h.

Constructor & Destructor Documentation

◆ CbRotate() [1/2]

cl_move_base_z::CbRotate::CbRotate ( )

Definition at line 7 of file cb_rotate.cpp.

8{
9}

◆ CbRotate() [2/2]

cl_move_base_z::CbRotate::CbRotate ( float  rotate_degree)

Definition at line 11 of file cb_rotate.cpp.

12{
13 rotateDegree = rotate_degree;
14}
boost::optional< float > rotateDegree
Definition: cb_rotate.h:18

References rotateDegree.

Member Function Documentation

◆ onEntry()

void cl_move_base_z::CbRotate::onEntry ( )
overridevirtual

Reimplemented from smacc::ISmaccClientBehavior.

Definition at line 16 of file cb_rotate.cpp.

17{
18 double angle_increment_degree;
19
20 if (!rotateDegree)
21 {
22 this->getCurrentState()->param("angle_increment_degree", angle_increment_degree, 45.0);
23 }
24 else
25 {
26 angle_increment_degree = *rotateDegree;
27 }
28
29 auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();
30 // this should work better with a coroutine and await
31 // this->plannerSwitcher_->setForwardPlanner();
32 plannerSwitcher->setDefaultPlanners();
33
35 auto referenceFrame = p->getReferenceFrame();
36 auto currentPoseMsg = p->toPoseMsg();
37
38 tf::Transform currentPose;
39 tf::poseMsgToTF(currentPoseMsg, currentPose);
40
41 auto odomTracker = moveBaseClient_->getComponent<odom_tracker::OdomTracker>();
42 ClMoveBaseZ::Goal goal;
43 goal.target_pose.header.frame_id = referenceFrame;
44 goal.target_pose.header.stamp = ros::Time::now();
45
46 auto currentAngle = tf::getYaw(currentPoseMsg.orientation);
47 auto targetAngle = currentAngle + angle_increment_degree * M_PI / 180.0;
48 goal.target_pose.pose.position = currentPoseMsg.position;
49 goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(targetAngle);
50
51 geometry_msgs::PoseStamped stampedCurrentPoseMsg;
52 stampedCurrentPoseMsg.header.frame_id = referenceFrame;
53 stampedCurrentPoseMsg.header.stamp = ros::Time::now();
54 stampedCurrentPoseMsg.pose = currentPoseMsg;
55
57 odomTracker->pushPath("RelativeRotation");
58
59 odomTracker->setStartPoint(stampedCurrentPoseMsg);
60 odomTracker->setWorkingMode(odom_tracker::WorkingMode::RECORD_PATH);
61
62 ROS_INFO_STREAM("current pose: " << currentPoseMsg);
63 ROS_INFO_STREAM("goal pose: " << goal.target_pose.pose);
65}
const std::string & getReferenceFrame() const
Definition: cp_pose.h:39
void requiresClient(SmaccClientType *&storage)
TComponent * getComponent()
bool param(std::string param_name, T &param_val, const T &default_val) const

References smacc::ISmaccClient::getComponent(), smacc::ISmaccClientBehavior::getCurrentState(), cl_move_base_z::Pose::getReferenceFrame(), cl_move_base_z::CbMoveBaseClientBehaviorBase::moveBaseClient_, smacc::ISmaccState::param(), cl_move_base_z::odom_tracker::RECORD_PATH, smacc::ISmaccClientBehavior::requiresClient(), rotateDegree, smacc::client_bases::SmaccActionClientBase< ActionType >::sendGoal(), and cl_move_base_z::PlannerSwitcher::setDefaultPlanners().

Here is the call graph for this function:

Member Data Documentation

◆ listener

tf::TransformListener cl_move_base_z::CbRotate::listener

Definition at line 16 of file cb_rotate.h.

◆ rotateDegree

boost::optional<float> cl_move_base_z::CbRotate::rotateDegree

Definition at line 18 of file cb_rotate.h.

Referenced by CbRotate(), and onEntry().


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