SMACC2
Loading...
Searching...
No Matches
cl_moveit2z::CpTfListener Class Reference

Component for shared TF2 transform management across all behaviors. More...

#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 ()=default
 
virtual ~CpTfListener ()=default
 
void onInitialize () override
 Initialize the shared TF2 buffer and listener.
 
std::optional< geometry_msgs::msg::TransformStamped > lookupTransform (const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time=rclcpp::Time(0))
 Thread-safe transform lookup.
 
std::optional< geometry_msgs::msg::PoseStamped > transformPose (const geometry_msgs::msg::PoseStamped &pose, const std::string &target_frame)
 Transform a pose to a different frame.
 
bool canTransform (const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time=rclcpp::Time(0), const rclcpp::Duration &timeout=rclcpp::Duration::from_seconds(0.0))
 Check if a transform is available.
 
std::shared_ptr< tf2_ros::Buffer > getBuffer ()
 Get raw access to the TF2 buffer for advanced use cases.
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Static Private Attributes

static std::shared_ptr< tf2_ros::Buffer > tfBuffer_ = nullptr
 
static std::shared_ptr< tf2_ros::TransformListener > tfListener_ = nullptr
 
static std::mutex tfMutex_
 

Additional Inherited Members

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

Detailed Description

Component for shared TF2 transform management across all behaviors.

This component provides centralized access to TF2 transforms using static resource sharing to avoid creating multiple tf2_ros::Buffer and tf2_ros::TransformListener instances across different behaviors.

Pattern: Static resource sharing (similar to nav2z_client's Pose component)

Definition at line 45 of file cp_tf_listener.hpp.

Constructor & Destructor Documentation

◆ CpTfListener()

cl_moveit2z::CpTfListener::CpTfListener ( )
default

◆ ~CpTfListener()

virtual cl_moveit2z::CpTfListener::~CpTfListener ( )
virtualdefault

Member Function Documentation

◆ canTransform()

bool cl_moveit2z::CpTfListener::canTransform ( const std::string & target_frame,
const std::string & source_frame,
const rclcpp::Time & time = rclcpp::Time(0),
const rclcpp::Duration & timeout = rclcpp::Duration::from_seconds(0.0) )
inline

Check if a transform is available.

Parameters
target_frameTarget frame
source_frameSource frame
timeTime to check for (default: latest)
timeoutHow long to wait for the transform
Returns
bool True if transform is available, false otherwise

Definition at line 151 of file cp_tf_listener.hpp.

155 {
156 std::lock_guard<std::mutex> guard(tfMutex_);
157
158 if (!tfBuffer_)
159 {
160 RCLCPP_ERROR(
161 getLogger(), "[CpTfListener] TF buffer not initialized. Call onInitialize() first.");
162 return false;
163 }
164
165 return tfBuffer_->canTransform(target_frame, source_frame, time, timeout);
166 }
static std::shared_ptr< tf2_ros::Buffer > tfBuffer_
rclcpp::Logger getLogger() const

References smacc2::ISmaccComponent::getLogger(), tfBuffer_, and tfMutex_.

Here is the call graph for this function:

◆ getBuffer()

std::shared_ptr< tf2_ros::Buffer > cl_moveit2z::CpTfListener::getBuffer ( )
inline

Get raw access to the TF2 buffer for advanced use cases.

WARNING: Direct buffer access bypasses thread safety. Use with caution.

Returns
std::shared_ptr<tf2_ros::Buffer> Shared pointer to the TF2 buffer

Definition at line 175 of file cp_tf_listener.hpp.

176 {
177 std::lock_guard<std::mutex> guard(tfMutex_);
178 return tfBuffer_;
179 }

References tfBuffer_, and tfMutex_.

◆ lookupTransform()

std::optional< geometry_msgs::msg::TransformStamped > cl_moveit2z::CpTfListener::lookupTransform ( const std::string & target_frame,
const std::string & source_frame,
const rclcpp::Time & time = rclcpp::Time(0) )
inline

Thread-safe transform lookup.

Parameters
target_frameTarget frame for the transform
source_frameSource frame for the transform
timeTime at which to get the transform (default: latest available)
Returns
std::optional<geometry_msgs::msg::TransformStamped> Transform if available, std::nullopt otherwise

Definition at line 81 of file cp_tf_listener.hpp.

84 {
85 std::lock_guard<std::mutex> guard(tfMutex_);
86
87 if (!tfBuffer_)
88 {
89 RCLCPP_ERROR(
90 getLogger(), "[CpTfListener] TF buffer not initialized. Call onInitialize() first.");
91 return std::nullopt;
92 }
93
94 try
95 {
96 auto transform = tfBuffer_->lookupTransform(target_frame, source_frame, time);
97 return transform;
98 }
99 catch (const tf2::TransformException & ex)
100 {
101 RCLCPP_WARN(
102 getLogger(), "[CpTfListener] Could not get transform from '%s' to '%s': %s",
103 source_frame.c_str(), target_frame.c_str(), ex.what());
104 return std::nullopt;
105 }
106 }

References smacc2::ISmaccComponent::getLogger(), tfBuffer_, and tfMutex_.

Referenced by cl_moveit2z::CbCircularPivotMotion::computeCurrentEndEffectorPoseRelativeToPivot(), cl_moveit2z::CbMoveEndEffectorTrajectory::getCurrentEndEffectorPose(), and cl_moveit2z::CbEndEffectorRotate::onEntry().

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

◆ onInitialize()

void cl_moveit2z::CpTfListener::onInitialize ( )
inlineoverridevirtual

Initialize the shared TF2 buffer and listener.

This method initializes the static tf2_ros::Buffer and tf2_ros::TransformListener on first use. Subsequent component instances will reuse the same resources.

Reimplemented from smacc2::ISmaccComponent.

Definition at line 57 of file cp_tf_listener.hpp.

58 {
59 std::lock_guard<std::mutex> guard(tfMutex_);
60
61 if (!tfBuffer_)
62 {
63 RCLCPP_INFO(getLogger(), "[CpTfListener] Initializing shared TF2 buffer and listener");
64 tfBuffer_ = std::make_shared<tf2_ros::Buffer>(getNode()->get_clock());
65 tfListener_ = std::make_shared<tf2_ros::TransformListener>(*tfBuffer_);
66 }
67 else
68 {
69 RCLCPP_DEBUG(getLogger(), "[CpTfListener] Reusing existing shared TF2 resources");
70 }
71 }
static std::shared_ptr< tf2_ros::TransformListener > tfListener_
rclcpp::Node::SharedPtr getNode()

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), tfBuffer_, tfListener_, and tfMutex_.

Here is the call graph for this function:

◆ transformPose()

std::optional< geometry_msgs::msg::PoseStamped > cl_moveit2z::CpTfListener::transformPose ( const geometry_msgs::msg::PoseStamped & pose,
const std::string & target_frame )
inline

Transform a pose to a different frame.

Parameters
poseInput pose in its original frame
target_frameTarget frame to transform the pose into
Returns
std::optional<geometry_msgs::msg::PoseStamped> Transformed pose if successful, std::nullopt otherwise

Definition at line 115 of file cp_tf_listener.hpp.

117 {
118 std::lock_guard<std::mutex> guard(tfMutex_);
119
120 if (!tfBuffer_)
121 {
122 RCLCPP_ERROR(
123 getLogger(), "[CpTfListener] TF buffer not initialized. Call onInitialize() first.");
124 return std::nullopt;
125 }
126
127 try
128 {
129 geometry_msgs::msg::PoseStamped transformed_pose;
130 tfBuffer_->transform(pose, transformed_pose, target_frame);
131 return transformed_pose;
132 }
133 catch (const tf2::TransformException & ex)
134 {
135 RCLCPP_WARN(
136 getLogger(), "[CpTfListener] Could not transform pose to frame '%s': %s",
137 target_frame.c_str(), ex.what());
138 return std::nullopt;
139 }
140 }

References smacc2::ISmaccComponent::getLogger(), tfBuffer_, and tfMutex_.

Here is the call graph for this function:

Member Data Documentation

◆ tfBuffer_

std::shared_ptr< tf2_ros::Buffer > cl_moveit2z::CpTfListener::tfBuffer_ = nullptr
staticprivate

◆ tfListener_

std::shared_ptr< tf2_ros::TransformListener > cl_moveit2z::CpTfListener::tfListener_ = nullptr
staticprivate

Definition at line 184 of file cp_tf_listener.hpp.

Referenced by onInitialize().

◆ tfMutex_

std::mutex cl_moveit2z::CpTfListener::tfMutex_
staticprivate

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