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]

List of all members.

Public Member Functions

bool getFrames (tf::FrameGraph::Request &req, 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.
 TransformListener (ros::Duration max_cache_time=ros::Duration(DEFAULT_CACHE_TIME), bool spin_thread=true)
 Constructor for transform listener.
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.
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.
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.
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.
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.
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.
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 Twist Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform.
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.
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.
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.
 ~TransformListener ()

Protected Member Functions

bool ok () const

Private Member Functions

void dedicatedListenerThread ()
void init ()
 Initialize this transform listener, subscribing, advertising services, etc.
void initWithThread ()
void subscription_callback (const tf::tfMessageConstPtr &msg)
 Callback function for ros message subscriptoin.
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

Private Attributes

boost::thread * dedicated_listener_thread_
std_msgs::Empty empty_
 clear the cached data
ros::Time last_update_ros_time_
 last time
ros::Subscriber message_subscriber_tf_
ros::NodeHandle node_
ros::Subscriber reset_time_subscriber_
ros::ServiceServer tf_frames_srv_
ros::CallbackQueue tf_message_callback_queue_

Detailed Description

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

Definition at line 66 of file transform_listener.h.


Constructor & Destructor Documentation

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

Constructor for transform listener.

Parameters:
max_cache_time How long to store transform information

Definition at line 78 of file transform_listener.cpp.

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:
nh The NodeHandle to use for any ROS interaction
max_cache_time How long to store transform information

Definition at line 87 of file transform_listener.cpp.

TransformListener::~TransformListener (  ) 

Definition at line 96 of file transform_listener.cpp.


Member Function Documentation

void tf::TransformListener::dedicatedListenerThread (  )  [inline, private]

Definition at line 180 of file transform_listener.h.

bool tf::TransformListener::getFrames ( tf::FrameGraph::Request req,
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 144 of file transform_listener.h.

void TransformListener::init (  )  [private]

Initialize this transform listener, subscribing, advertising services, etc.

Todo:
magic number

Definition at line 109 of file transform_listener.cpp.

void TransformListener::initWithThread (  )  [private]

Todo:
magic number

Definition at line 126 of file transform_listener.cpp.

bool TransformListener::ok (  )  const [protected, virtual]

Reimplemented from tf::Transformer.

Definition at line 107 of file transform_listener.cpp.

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

Definition at line 151 of file transform_listener.h.

void TransformListener::subscription_callback ( const tf::tfMessageConstPtr msg  )  [private]

Callback function for ros message subscriptoin.

Todo:
Use error reporting

Definition at line 335 of file transform_listener.cpp.

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 243 of file transform_listener.cpp.

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 168 of file transform_listener.cpp.

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 288 of file transform_listener.cpp.

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 272 of file transform_listener.cpp.

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 265 of file transform_listener.cpp.

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 253 of file transform_listener.cpp.

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 178 of file transform_listener.cpp.

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 Twist Message into the target frame This can throw all that lookupTransform can throw as well as tf::InvalidTransform.

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 222 of file transform_listener.cpp.

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 146 of file transform_listener.cpp.

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 233 of file transform_listener.cpp.

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 158 of file transform_listener.cpp.


Member Data Documentation

Definition at line 176 of file transform_listener.h.

std_msgs::Empty tf::TransformListener::empty_ [private]

clear the cached data

Definition at line 171 of file transform_listener.h.

last time

Definition at line 154 of file transform_listener.h.

Definition at line 178 of file transform_listener.h.

ros::NodeHandle tf::TransformListener::node_ [private]

Definition at line 177 of file transform_listener.h.

Definition at line 178 of file transform_listener.h.

ros::ServiceServer tf::TransformListener::tf_frames_srv_ [private]

Definition at line 172 of file transform_listener.h.

Definition at line 175 of file transform_listener.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Fri Jan 11 09:09:57 2013