SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Protected Attributes | List of all members
cl_nav2z::CbWaitTransform Class Reference

#include <cb_wait_transform.hpp>

Inheritance diagram for cl_nav2z::CbWaitTransform:
Inheritance graph
Collaboration diagram for cl_nav2z::CbWaitTransform:
Collaboration graph

Public Member Functions

 CbWaitTransform (std::string targetFrame, std::string referenceFrame, rclcpp::Duration timeout)
 
virtual ~CbWaitTransform ()
 
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)
 
void requestForceFinish ()
 
void executeOnEntry () override
 
void executeOnExit () override
 
void waitOnEntryThread (bool requestFinish)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onSuccess (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFinished (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFailure (TCallbackMethod 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, bool throwExceptionIfNotExist=false)
 
virtual void onExit ()
 

Protected Attributes

std::shared_ptr< tf2_ros::Buffer > tfBuffer_
 
std::shared_ptr< tf2_ros::TransformListener > tfListener_
 
std::string targetFrame_
 
std::string referenceFrame_
 
rclcpp::Duration timeout_
 
std::optional< tf2::Stamped< tf2::Transform > > result_
 

Additional Inherited Members

- Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior
void postSuccessEvent ()
 
void postFailureEvent ()
 
virtual void dispose () override
 
bool isShutdownRequested ()
 onEntry is executed in a new thread. However the current state cannot be left until the onEntry thread finishes. This flag can be checked from the onEntry thread to force finishing the thread.
 
- Protected Member Functions inherited from smacc2::ISmaccClientBehavior
virtual void runtimeConfigure ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
ISmaccStategetCurrentState ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 

Detailed Description

Definition at line 34 of file cb_wait_transform.hpp.

Constructor & Destructor Documentation

◆ CbWaitTransform()

cl_nav2z::CbWaitTransform::CbWaitTransform ( std::string  targetFrame,
std::string  referenceFrame,
rclcpp::Duration  timeout 
)

Definition at line 24 of file cb_wait_transform.cpp.

26: targetFrame_(targetFrame), referenceFrame_(referenceFrame), timeout_(timeout)
27{
28}

◆ ~CbWaitTransform()

cl_nav2z::CbWaitTransform::~CbWaitTransform ( )
virtual

Definition at line 30 of file cb_wait_transform.cpp.

30{}

Member Function Documentation

◆ onEntry()

void cl_nav2z::CbWaitTransform::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 32 of file cb_wait_transform.cpp.

33{
34 RCLCPP_INFO(
35 getLogger(), "[CbWaitTransform] ref %s -> target %s", referenceFrame_.c_str(),
36 targetFrame_.c_str());
37
38 tfBuffer_ = std::make_shared<tf2_ros::Buffer>(getNode()->get_clock());
39 tfListener_ = std::make_shared<tf2_ros::TransformListener>(*tfBuffer_);
40
41 tf2::Stamped<tf2::Transform> transform;
42 try
43 {
44 auto transformstamped =
45 tfBuffer_->lookupTransform(targetFrame_, referenceFrame_, getNode()->now(), timeout_);
46 tf2::fromMsg(transformstamped, transform);
47
48 result_ = transform;
49
50 RCLCPP_INFO(
51 getLogger(), "[CbWaitTransform] Success wait transform ref %s -> target %s",
52 referenceFrame_.c_str(), targetFrame_.c_str());
53 this->postSuccessEvent();
54 }
55 catch (tf2::TransformException & ex)
56 {
57 RCLCPP_ERROR_STREAM(
58 getLogger(), "[CbWaitTransform] Failure waiting transform ( ref "
59 << targetFrame_ << "/ target " << referenceFrame_ << " - " << ex.what());
60 this->postFailureEvent();
61 }
62}
std::shared_ptr< tf2_ros::TransformListener > tfListener_
std::shared_ptr< tf2_ros::Buffer > tfBuffer_
std::optional< tf2::Stamped< tf2::Transform > > result_
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const

References smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getNode(), smacc2::SmaccAsyncClientBehavior::postFailureEvent(), smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), referenceFrame_, result_, targetFrame_, tfBuffer_, tfListener_, and timeout_.

Here is the call graph for this function:

◆ onOrthogonalAllocation()

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

Definition at line 42 of file cb_wait_transform.hpp.

43 {
44 smacc2::SmaccAsyncClientBehavior::onOrthogonalAllocation<TOrthogonal, TSourceObject>();
45 }

Member Data Documentation

◆ referenceFrame_

std::string cl_nav2z::CbWaitTransform::referenceFrame_
protected

Definition at line 55 of file cb_wait_transform.hpp.

Referenced by onEntry().

◆ result_

std::optional<tf2::Stamped<tf2::Transform> > cl_nav2z::CbWaitTransform::result_
protected

Definition at line 58 of file cb_wait_transform.hpp.

Referenced by onEntry().

◆ targetFrame_

std::string cl_nav2z::CbWaitTransform::targetFrame_
protected

Definition at line 54 of file cb_wait_transform.hpp.

Referenced by onEntry().

◆ tfBuffer_

std::shared_ptr<tf2_ros::Buffer> cl_nav2z::CbWaitTransform::tfBuffer_
protected

Definition at line 51 of file cb_wait_transform.hpp.

Referenced by onEntry().

◆ tfListener_

std::shared_ptr<tf2_ros::TransformListener> cl_nav2z::CbWaitTransform::tfListener_
protected

Definition at line 52 of file cb_wait_transform.hpp.

Referenced by onEntry().

◆ timeout_

rclcpp::Duration cl_nav2z::CbWaitTransform::timeout_
protected

Definition at line 56 of file cb_wait_transform.hpp.

Referenced by onEntry().


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