SMACC2
Public Member Functions | Protected Attributes | List of all members
cl_nav2z::CbWaitPose Class Reference

#include <cb_wait_pose.hpp>

Inheritance diagram for cl_nav2z::CbWaitPose:
Inheritance graph
Collaboration diagram for cl_nav2z::CbWaitPose:
Collaboration graph

Public Member Functions

 CbWaitPose ()
 
 CbWaitPose (WaitPoseStandardReferenceFrame frame)
 
virtual ~CbWaitPose ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
void onEntry () override
 
- 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 ()
 
ISmaccStateMachinegetStateMachine ()
 
std::string getName () const
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage)
 

Protected Attributes

cl_nav2z::ClNav2ZmoveBaseClient_
 

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 ()
 
ISmaccStategetCurrentState ()
 
virtual void dispose ()
 
virtual rclcpp::Node::SharedPtr getNode ()
 
virtual rclcpp::Logger getLogger ()
 

Detailed Description

Definition at line 36 of file cb_wait_pose.hpp.

Constructor & Destructor Documentation

◆ CbWaitPose() [1/2]

cl_nav2z::CbWaitPose::CbWaitPose ( )

Definition at line 29 of file cb_wait_pose.cpp.

29{}

◆ CbWaitPose() [2/2]

cl_nav2z::CbWaitPose::CbWaitPose ( WaitPoseStandardReferenceFrame  frame)

◆ ~CbWaitPose()

cl_nav2z::CbWaitPose::~CbWaitPose ( )
virtual

Definition at line 31 of file cb_wait_pose.cpp.

31{}

Member Function Documentation

◆ onEntry()

void cl_nav2z::CbWaitPose::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 33 of file cb_wait_pose.cpp.

34{
35 auto pose = this->moveBaseClient_->getComponent<Pose>();
36 try
37 {
38 pose->waitTransformUpdate(rclcpp::Rate(20));
39 auto posemsg = pose->toPoseMsg();
40 RCLCPP_INFO_STREAM(getLogger(), "[CbWaitPose] pose arrived: " << std::endl << posemsg);
41 }
42 catch (std::exception & ex)
43 {
44 RCLCPP_INFO(getLogger(), "[CbWaitPose] error getting the robot pose");
45 this->postFailureEvent();
46 return;
47 }
48
49 RCLCPP_INFO(getLogger(), "[CbWaitPose] pose received");
50 this->postSuccessEvent();
51}
cl_nav2z::ClNav2Z * moveBaseClient_
TComponent * getComponent()

References smacc2::ISmaccClient::getComponent(), smacc2::ISmaccClientBehavior::getLogger(), moveBaseClient_, smacc2::SmaccAsyncClientBehavior::postFailureEvent(), smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), and cl_nav2z::Pose::waitTransformUpdate().

Here is the call graph for this function:

◆ onOrthogonalAllocation()

template<typename TOrthogonal , typename TSourceObject >
void cl_nav2z::CbWaitPose::onOrthogonalAllocation ( )
inline

Definition at line 48 of file cb_wait_pose.hpp.

49 {
51 smacc2::SmaccAsyncClientBehavior::onOrthogonalAllocation<TOrthogonal, TSourceObject>();
52 }
void requiresClient(SmaccClientType *&storage)

References moveBaseClient_, and smacc2::ISmaccClientBehavior::requiresClient().

Here is the call graph for this function:

Member Data Documentation

◆ moveBaseClient_

cl_nav2z::ClNav2Z* cl_nav2z::CbWaitPose::moveBaseClient_
protected

Definition at line 57 of file cb_wait_pose.hpp.

Referenced by onEntry(), and onOrthogonalAllocation().


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