|
SMACC2
|
Component for shared TF2 transform management across all behaviors. More...
#include <cp_tf_listener.hpp>


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 |
| ISmaccStateMachine * | getStateMachine () |
Protected Attributes inherited from smacc2::ISmaccComponent | |
| ISmaccStateMachine * | stateMachine_ |
| ISmaccClient * | owner_ |
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.
|
default |
|
virtualdefault |
|
inline |
Check if a transform is available.
| target_frame | Target frame |
| source_frame | Source frame |
| time | Time to check for (default: latest) |
| timeout | How long to wait for the transform |
Definition at line 151 of file cp_tf_listener.hpp.
References smacc2::ISmaccComponent::getLogger(), tfBuffer_, and tfMutex_.

|
inline |
Get raw access to the TF2 buffer for advanced use cases.
WARNING: Direct buffer access bypasses thread safety. Use with caution.
Definition at line 175 of file cp_tf_listener.hpp.
|
inline |
Thread-safe transform lookup.
| target_frame | Target frame for the transform |
| source_frame | Source frame for the transform |
| time | Time at which to get the transform (default: latest available) |
Definition at line 81 of file cp_tf_listener.hpp.
References smacc2::ISmaccComponent::getLogger(), tfBuffer_, and tfMutex_.
Referenced by cl_moveit2z::CbCircularPivotMotion::computeCurrentEndEffectorPoseRelativeToPivot(), cl_moveit2z::CbMoveEndEffectorTrajectory::getCurrentEndEffectorPose(), and cl_moveit2z::CbEndEffectorRotate::onEntry().


|
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.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), tfBuffer_, tfListener_, and tfMutex_.

|
inline |
Transform a pose to a different frame.
| pose | Input pose in its original frame |
| target_frame | Target frame to transform the pose into |
Definition at line 115 of file cp_tf_listener.hpp.
References smacc2::ISmaccComponent::getLogger(), tfBuffer_, and tfMutex_.

|
staticprivate |
Definition at line 183 of file cp_tf_listener.hpp.
Referenced by canTransform(), getBuffer(), lookupTransform(), onInitialize(), and transformPose().
|
staticprivate |
Definition at line 184 of file cp_tf_listener.hpp.
Referenced by onInitialize().
|
staticprivate |
Definition at line 185 of file cp_tf_listener.hpp.
Referenced by canTransform(), getBuffer(), lookupTransform(), onInitialize(), and transformPose().