SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Private Attributes | Static Private Attributes | List of all members
cl_moveit2z::CpTFListener Class Reference

#include <cp_tf_listener.hpp>

Inheritance diagram for cl_moveit2z::CpTFListener:
Inheritance graph
Collaboration diagram for cl_moveit2z::CpTFListener:
Collaboration graph

Public Member Functions

 CpTFListener ()
 
virtual void update () override
 
void getLastTransform (std::string &targetPoseFrameName, std::string &referenceBaseFrame, geometry_msgs::msg::Pose &out)
 
std::future< geometry_msgs::msg::Pose > waitForNextTransform (std::string &targetName, std::string &referenceBaseFrame)
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 
- Public Member Functions inherited from smacc2::ISmaccUpdatable
 ISmaccUpdatable ()
 
 ISmaccUpdatable (rclcpp::Duration duration)
 
void executeUpdate (rclcpp::Node::SharedPtr node)
 
void setUpdatePeriod (rclcpp::Duration duration)
 

Private Attributes

std::mutex m_mutex_
 
std::list< std::shared_ptr< TfPoseTrack > > poseTracks_
 

Static Private Attributes

static std::shared_ptr< tf2_ros::TransformListener > tfListener_
 
static std::mutex listenerMutex_
 

Additional Inherited Members

- Protected Member Functions inherited from smacc2::ISmaccComponent
virtual void onInitialize ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentTypecreateSiblingComponent (TArgs... targs)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentTypecreateSiblingNamedComponent (std::string name, TArgs... targs)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger () const
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Definition at line 44 of file cp_tf_listener.hpp.

Constructor & Destructor Documentation

◆ CpTFListener()

cl_moveit2z::CpTFListener::CpTFListener ( )

Member Function Documentation

◆ getLastTransform()

void cl_moveit2z::CpTFListener::getLastTransform ( std::string &  targetPoseFrameName,
std::string &  referenceBaseFrame,
geometry_msgs::msg::Pose &  out 
)
inline

Definition at line 80 of file cp_tf_listener.hpp.

83 {
84 }

◆ update()

virtual void cl_moveit2z::CpTFListener::update ( )
inlineoverridevirtual

Implements smacc2::ISmaccUpdatable.

Definition at line 49 of file cp_tf_listener.hpp.

50 {
51 for (auto & poseTrack : poseTracks_)
52 {
53 tf2::Stamped<tf2::Transform> transform;
54 try
55 {
56 {
57 std::lock_guard<std::mutex> lock(listenerMutex_);
58 tfListener_->lookupTransform(
59 poseTrack->referenceBaseFrame_, poseTrack->targetPoseFrame_, rclcpp::Time(0),
60 transform);
61 }
62
63 {
64 std::lock_guard<std::mutex> guard(m_mutex_);
65 poseTrack->pose_.pose = tf2::toMsg(transform);
66 poseTrack->pose_.header.stamp = transform.stamp_;
67 poseTrack->pose_.header.frame_id = poseTrack->referenceBaseFrame_;
68 poseTrack->isInitialized = true;
69 }
70 }
71 catch (tf2::TransformException ex)
72 {
73 RCLCPP_ERROR_STREAM_THROTTLE(
74 1, "[Component pose] (getLogger(), " << poseFrameName_ << "/[" << referenceFrame_
75 << "] ) is failing on pose update : " << ex.what());
76 }
77 }
78 }
std::list< std::shared_ptr< TfPoseTrack > > poseTracks_
static std::mutex listenerMutex_
static std::shared_ptr< tf2_ros::TransformListener > tfListener_

References listenerMutex_, m_mutex_, poseTracks_, and tfListener_.

◆ waitForNextTransform()

std::future< geometry_msgs::msg::Pose > cl_moveit2z::CpTFListener::waitForNextTransform ( std::string &  targetName,
std::string &  referenceBaseFrame 
)
inline

Definition at line 86 of file cp_tf_listener.hpp.

88 {
89 tracks_
90 }

Member Data Documentation

◆ listenerMutex_

std::mutex cl_moveit2z::CpTFListener::listenerMutex_
staticprivate

Definition at line 94 of file cp_tf_listener.hpp.

Referenced by update().

◆ m_mutex_

std::mutex cl_moveit2z::CpTFListener::m_mutex_
private

Definition at line 96 of file cp_tf_listener.hpp.

Referenced by update().

◆ poseTracks_

std::list<std::shared_ptr<TfPoseTrack> > cl_moveit2z::CpTFListener::poseTracks_
private

Definition at line 97 of file cp_tf_listener.hpp.

Referenced by update().

◆ tfListener_

std::shared_ptr<tf2_ros::TransformListener> cl_moveit2z::CpTFListener::tfListener_
staticprivate

Definition at line 93 of file cp_tf_listener.hpp.

Referenced by update().


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