Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
tf::TransformListener Class Reference

This class inherits from Transformer and automatically subscribes to ROS transform messages. More...

#include <transform_listener.h>

Inheritance diagram for tf::TransformListener:
Inheritance graph
[legend]

Public Member Functions

bool getFrames (tf::FrameGraph::Request &, tf::FrameGraph::Response &res)
 
std::string resolve (const std::string &frame_name)
 
 TransformListener (const ros::NodeHandle &nh, ros::Duration max_cache_time=ros::Duration(DEFAULT_CACHE_TIME), bool spin_thread=true)
 Alternate constructor for transform listener. More...
 
 TransformListener (ros::Duration max_cache_time=ros::Duration(DEFAULT_CACHE_TIME), bool spin_thread=true)
 Constructor for transform listener. More...
 
void transformPoint (const std::string &target_frame, const geometry_msgs::PointStamped &stamped_in, geometry_msgs::PointStamped &stamped_out) const
 Transform a Stamped Point Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform. More...
 
void transformPoint (const std::string &target_frame, const ros::Time &target_time, const geometry_msgs::PointStamped &pin, const std::string &fixed_frame, geometry_msgs::PointStamped &pout) const
 Transform a Stamped Point Message into the target frame and time
This can throw all that lookupTransform can throw as well as tf::InvalidTransform. More...
 
void transformPoint (const std::string &target_frame, const ros::Time &target_time, const Stamped< tf::Point > &stamped_in, const std::string &fixed_frame, Stamped< tf::Point > &stamped_out) const
 Transform a Stamped Point into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformPoint (const std::string &target_frame, const Stamped< tf::Point > &stamped_in, Stamped< tf::Point > &stamped_out) const
 Transform a Stamped Point into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformPointCloud (const std::string &target_frame, const ros::Time &target_time, const sensor_msgs::PointCloud &pcin, const std::string &fixed_frame, sensor_msgs::PointCloud &pcout) const
 Transform a sensor_msgs::PointCloud in space and time This can throw all that lookupTransform can throw as well as tf::InvalidTransform. More...
 
void transformPointCloud (const std::string &target_frame, const sensor_msgs::PointCloud &pcin, sensor_msgs::PointCloud &pcout) const
 Transform a sensor_msgs::PointCloud natively This can throw all that lookupTransform can throw as well as tf::InvalidTransform. More...
 
void transformPose (const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
 Transform a Stamped Pose Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform. More...
 
void transformPose (const std::string &target_frame, const ros::Time &target_time, const geometry_msgs::PoseStamped &pin, const std::string &fixed_frame, geometry_msgs::PoseStamped &pout) const
 Transform a Stamped Pose Message into the target frame and time
This can throw all that lookupTransform can throw as well as tf::InvalidTransform. More...
 
void transformPose (const std::string &target_frame, const ros::Time &target_time, const Stamped< tf::Pose > &stamped_in, const std::string &fixed_frame, Stamped< tf::Pose > &stamped_out) const
 Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformPose (const std::string &target_frame, const Stamped< tf::Pose > &stamped_in, Stamped< tf::Pose > &stamped_out) const
 Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformQuaternion (const std::string &target_frame, const geometry_msgs::QuaternionStamped &stamped_in, geometry_msgs::QuaternionStamped &stamped_out) const
 Transform a Stamped Quaternion Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform. More...
 
void transformQuaternion (const std::string &target_frame, const ros::Time &target_time, const geometry_msgs::QuaternionStamped &qin, const std::string &fixed_frame, geometry_msgs::QuaternionStamped &qout) const
 Transform a Stamped Quaternion Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform. More...
 
void transformQuaternion (const std::string &target_frame, const ros::Time &target_time, const Stamped< tf::Quaternion > &stamped_in, const std::string &fixed_frame, Stamped< tf::Quaternion > &stamped_out) const
 Transform a Stamped Quaternion into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformQuaternion (const std::string &target_frame, const Stamped< tf::Quaternion > &stamped_in, Stamped< tf::Quaternion > &stamped_out) const
 Transform a Stamped Quaternion into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformVector (const std::string &target_frame, const geometry_msgs::Vector3Stamped &stamped_in, geometry_msgs::Vector3Stamped &stamped_out) const
 Transform a Stamped Vector Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform. More...
 
void transformVector (const std::string &target_frame, const ros::Time &target_time, const geometry_msgs::Vector3Stamped &vin, const std::string &fixed_frame, geometry_msgs::Vector3Stamped &vout) const
 Transform a Stamped Vector Message into the target frame and time This can throw all that lookupTransform can throw as well as tf::InvalidTransform. More...
 
void transformVector (const std::string &target_frame, const ros::Time &target_time, const Stamped< tf::Vector3 > &stamped_in, const std::string &fixed_frame, Stamped< tf::Vector3 > &stamped_out) const
 Transform a Stamped Vector3 into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformVector (const std::string &target_frame, const Stamped< tf::Vector3 > &stamped_in, Stamped< tf::Vector3 > &stamped_out) const
 Transform a Stamped Vector3 into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
 ~TransformListener ()
 
- Public Member Functions inherited from tf::Transformer
boost::signals2::connection addTransformsChangedListener (boost::function< void(void)> callback)
 Add a callback that happens when a new transform has arrived. More...
 
std::string allFramesAsDot (double current_time=0) const
 A way to see what frames have been cached Useful for debugging. More...
 
std::string allFramesAsString () const
 A way to see what frames have been cached Useful for debugging. More...
 
bool canTransform (const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, std::string *error_msg=NULL) const
 Test if a transform is possible. More...
 
bool canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
 Test if a transform is possible. More...
 
void chainAsVector (const std::string &target_frame, ros::Time target_time, const std::string &source_frame, ros::Time source_time, const std::string &fixed_frame, std::vector< std::string > &output) const
 Debugging function that will print the spanning chain of transforms. Possible exceptions tf::LookupException, tf::ConnectivityException, tf::MaxDepthException. More...
 
void clear ()
 Clear all data. More...
 
bool frameExists (const std::string &frame_id_str) const
 Check if a frame exists in the tree. More...
 
ros::Duration getCacheLength ()
 Get the duration over which this transformer will cache. More...
 
void getFrameStrings (std::vector< std::string > &ids) const
 A way to get a std::vector of available frame ids. More...
 
int getLatestCommonTime (const std::string &source_frame, const std::string &target_frame, ros::Time &time, std::string *error_string) const
 Return the latest rostime which is common across the spanning set zero if fails to cross. More...
 
bool getParent (const std::string &frame_id, ros::Time time, std::string &parent) const
 Fill the parent of a frame. More...
 
std::shared_ptr< tf2_ros::BuffergetTF2BufferPtr ()
 
std::string getTFPrefix () const
 Get the tf_prefix this is running with. More...
 
bool isUsingDedicatedThread ()
 
void lookupTransform (const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
 Get the transform between two frames by frame ID assuming fixed frame. More...
 
void lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
 Get the transform between two frames by frame ID. More...
 
void lookupTwist (const std::string &tracking_frame, const std::string &observation_frame, const ros::Time &time, const ros::Duration &averaging_interval, geometry_msgs::Twist &twist) const
 lookup the twist of the tracking frame with respect to the observational frame More...
 
void lookupTwist (const std::string &tracking_frame, const std::string &observation_frame, const std::string &reference_frame, const tf::Point &reference_point, const std::string &reference_point_frame, const ros::Time &time, const ros::Duration &averaging_interval, geometry_msgs::Twist &twist) const
 Lookup the twist of the tracking_frame with respect to the observation frame in the reference_frame using the reference point. More...
 
void removeTransformsChangedListener (boost::signals2::connection c)
 
void setExtrapolationLimit (const ros::Duration &distance)
 Set the distance which tf is allow to extrapolate. More...
 
bool setTransform (const StampedTransform &transform, const std::string &authority="default_authority")
 Add transform information to the tf data structure. More...
 
void setUsingDedicatedThread (bool value)
 
 Transformer (bool interpolating=true, ros::Duration cache_time_=ros::Duration(DEFAULT_CACHE_TIME))
 
void transformPoint (const std::string &target_frame, const ros::Time &target_time, const Stamped< tf::Point > &stamped_in, const std::string &fixed_frame, Stamped< tf::Point > &stamped_out) const
 Transform a Stamped Point into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformPoint (const std::string &target_frame, const Stamped< tf::Point > &stamped_in, Stamped< tf::Point > &stamped_out) const
 Transform a Stamped Point into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformPose (const std::string &target_frame, const ros::Time &target_time, const Stamped< tf::Pose > &stamped_in, const std::string &fixed_frame, Stamped< tf::Pose > &stamped_out) const
 Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformPose (const std::string &target_frame, const Stamped< tf::Pose > &stamped_in, Stamped< tf::Pose > &stamped_out) const
 Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformQuaternion (const std::string &target_frame, const ros::Time &target_time, const Stamped< tf::Quaternion > &stamped_in, const std::string &fixed_frame, Stamped< tf::Quaternion > &stamped_out) const
 Transform a Stamped Quaternion into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformQuaternion (const std::string &target_frame, const Stamped< tf::Quaternion > &stamped_in, Stamped< tf::Quaternion > &stamped_out) const
 Transform a Stamped Quaternion into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformVector (const std::string &target_frame, const ros::Time &target_time, const Stamped< tf::Vector3 > &stamped_in, const std::string &fixed_frame, Stamped< tf::Vector3 > &stamped_out) const
 Transform a Stamped Vector3 into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformVector (const std::string &target_frame, const Stamped< tf::Vector3 > &stamped_in, Stamped< tf::Vector3 > &stamped_out) const
 Transform a Stamped Vector3 into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
bool waitForTransform (const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
 Block until a transform is possible or it times out. More...
 
bool waitForTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
 Block until a transform is possible or it times out. More...
 
virtual ~Transformer (void)
 

Protected Member Functions

bool ok () const
 
- Protected Member Functions inherited from tf::Transformer
ros::Time now () const
 

Private Member Functions

void transformPointCloud (const std::string &target_frame, const Transform &transform, const ros::Time &target_time, const sensor_msgs::PointCloud &pcin, sensor_msgs::PointCloud &pcout) const
 a helper function to be used for both transfrom pointCloud methods More...
 

Private Attributes

ros::NodeHandle node_
 
tf2_ros::TransformListener tf2_listener_
 replacing implementation with tf2_ros' More...
 

Additional Inherited Members

- Public Attributes inherited from tf::Transformer
bool fall_back_to_wall_time_
 
- Static Public Attributes inherited from tf::Transformer
static const double DEFAULT_CACHE_TIME = 10.0
 10.0 is the default amount of time to cache data in seconds, set in cpp file. More...
 
static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0ULL
 The default amount of time to extrapolate //deprecated since integration with tf2. More...
 
static const unsigned int MAX_GRAPH_DEPTH = 100UL
 The maximum number of time to recurse before assuming the tree has a loop. More...
 
- Protected Attributes inherited from tf::Transformer
std::shared_ptr< tf2_ros::Buffertf2_buffer_ptr_
 
std::string tf_prefix_
 The internal storage class for ReferenceTransform. More...
 

Detailed Description

This class inherits from Transformer and automatically subscribes to ROS transform messages.

Definition at line 70 of file transform_listener.h.

Constructor & Destructor Documentation

◆ TransformListener() [1/2]

TransformListener::TransformListener ( ros::Duration  max_cache_time = ros::Duration(DEFAULT_CACHE_TIME),
bool  spin_thread = true 
)

Constructor for transform listener.

Parameters
max_cache_timeHow long to store transform information

Definition at line 43 of file transform_listener.cpp.

◆ TransformListener() [2/2]

TransformListener::TransformListener ( const ros::NodeHandle nh,
ros::Duration  max_cache_time = ros::Duration(DEFAULT_CACHE_TIME),
bool  spin_thread = true 
)

Alternate constructor for transform listener.

Parameters
nhThe NodeHandle to use for any ROS interaction
max_cache_timeHow long to store transform information

Definition at line 49 of file transform_listener.cpp.

◆ ~TransformListener()

TransformListener::~TransformListener ( )

Definition at line 55 of file transform_listener.cpp.

Member Function Documentation

◆ getFrames()

bool tf::TransformListener::getFrames ( tf::FrameGraph::Request &  ,
tf::FrameGraph::Response &  res 
)
inline
Todo:
move to high precision laser projector class void projectAndTransformLaserScan(const sensor_msgs::LaserScan& scan_in, sensor_msgs::PointCloud& pcout);

Definition at line 148 of file transform_listener.h.

◆ ok()

bool TransformListener::ok ( ) const
protectedvirtual

Reimplemented from tf::Transformer.

Definition at line 61 of file transform_listener.cpp.

◆ resolve()

std::string tf::TransformListener::resolve ( const std::string &  frame_name)
inline

Definition at line 155 of file transform_listener.h.

◆ transformPoint() [1/4]

void TransformListener::transformPoint ( const std::string &  target_frame,
const geometry_msgs::PointStamped &  stamped_in,
geometry_msgs::PointStamped &  stamped_out 
) const

Transform a Stamped Point Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform.

Definition at line 87 of file transform_listener.cpp.

◆ transformPoint() [2/4]

void TransformListener::transformPoint ( const std::string &  target_frame,
const ros::Time target_time,
const geometry_msgs::PointStamped &  pin,
const std::string &  fixed_frame,
geometry_msgs::PointStamped &  pout 
) const

Transform a Stamped Point Message into the target frame and time
This can throw all that lookupTransform can throw as well as tf::InvalidTransform.

Definition at line 162 of file transform_listener.cpp.

◆ transformPoint() [3/4]

void Transformer::transformPoint

Transform a Stamped Point into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Definition at line 543 of file tf.cpp.

◆ transformPoint() [4/4]

void Transformer::transformPoint

Transform a Stamped Point into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Definition at line 484 of file tf.cpp.

◆ transformPointCloud() [1/3]

void TransformListener::transformPointCloud ( const std::string &  target_frame,
const ros::Time target_time,
const sensor_msgs::PointCloud &  pcin,
const std::string &  fixed_frame,
sensor_msgs::PointCloud &  pcout 
) const

Transform a sensor_msgs::PointCloud in space and time This can throw all that lookupTransform can throw as well as tf::InvalidTransform.

Definition at line 191 of file transform_listener.cpp.

◆ transformPointCloud() [2/3]

void TransformListener::transformPointCloud ( const std::string &  target_frame,
const sensor_msgs::PointCloud &  pcin,
sensor_msgs::PointCloud &  pcout 
) const

Transform a sensor_msgs::PointCloud natively This can throw all that lookupTransform can throw as well as tf::InvalidTransform.

Definition at line 184 of file transform_listener.cpp.

◆ transformPointCloud() [3/3]

void TransformListener::transformPointCloud ( const std::string &  target_frame,
const Transform transform,
const ros::Time target_time,
const sensor_msgs::PointCloud &  pcin,
sensor_msgs::PointCloud &  pcout 
) const
private

a helper function to be used for both transfrom pointCloud methods

Definition at line 217 of file transform_listener.cpp.

◆ transformPose() [1/4]

void TransformListener::transformPose ( const std::string &  target_frame,
const geometry_msgs::PoseStamped &  stamped_in,
geometry_msgs::PoseStamped &  stamped_out 
) const

Transform a Stamped Pose Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform.

Definition at line 97 of file transform_listener.cpp.

◆ transformPose() [2/4]

void TransformListener::transformPose ( const std::string &  target_frame,
const ros::Time target_time,
const geometry_msgs::PoseStamped &  pin,
const std::string &  fixed_frame,
geometry_msgs::PoseStamped &  pout 
) const

Transform a Stamped Pose Message into the target frame and time
This can throw all that lookupTransform can throw as well as tf::InvalidTransform.

Definition at line 172 of file transform_listener.cpp.

◆ transformPose() [3/4]

void Transformer::transformPose

Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Definition at line 558 of file tf.cpp.

◆ transformPose() [4/4]

void Transformer::transformPose

Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Definition at line 494 of file tf.cpp.

◆ transformQuaternion() [1/4]

void TransformListener::transformQuaternion ( const std::string &  target_frame,
const geometry_msgs::QuaternionStamped &  stamped_in,
geometry_msgs::QuaternionStamped &  stamped_out 
) const

Transform a Stamped Quaternion Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform.

Definition at line 65 of file transform_listener.cpp.

◆ transformQuaternion() [2/4]

void TransformListener::transformQuaternion ( const std::string &  target_frame,
const ros::Time target_time,
const geometry_msgs::QuaternionStamped &  qin,
const std::string &  fixed_frame,
geometry_msgs::QuaternionStamped &  qout 
) const

Transform a Stamped Quaternion Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform.

Definition at line 141 of file transform_listener.cpp.

◆ transformQuaternion() [3/4]

void Transformer::transformQuaternion

Transform a Stamped Quaternion into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Definition at line 505 of file tf.cpp.

◆ transformQuaternion() [4/4]

void Transformer::transformQuaternion

Transform a Stamped Quaternion into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Definition at line 453 of file tf.cpp.

◆ transformVector() [1/4]

void TransformListener::transformVector ( const std::string &  target_frame,
const geometry_msgs::Vector3Stamped &  stamped_in,
geometry_msgs::Vector3Stamped &  stamped_out 
) const

Transform a Stamped Vector Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform.

Definition at line 77 of file transform_listener.cpp.

◆ transformVector() [2/4]

void TransformListener::transformVector ( const std::string &  target_frame,
const ros::Time target_time,
const geometry_msgs::Vector3Stamped &  vin,
const std::string &  fixed_frame,
geometry_msgs::Vector3Stamped &  vout 
) const

Transform a Stamped Vector Message into the target frame and time This can throw all that lookupTransform can throw as well as tf::InvalidTransform.

Definition at line 152 of file transform_listener.cpp.

◆ transformVector() [3/4]

void tf::Transformer::transformVector

Transform a Stamped Vector3 into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

◆ transformVector() [4/4]

void Transformer::transformVector

Transform a Stamped Vector3 into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Todo:
may not be most efficient

Definition at line 466 of file tf.cpp.

Member Data Documentation

◆ node_

ros::NodeHandle tf::TransformListener::node_
private

Definition at line 168 of file transform_listener.h.

◆ tf2_listener_

tf2_ros::TransformListener tf::TransformListener::tf2_listener_
private

replacing implementation with tf2_ros'

Definition at line 171 of file transform_listener.h.


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


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sat Aug 19 2023 02:38:08