tf2::BufferInterface Class Reference

#include <buffer_interface.h>

Inheritance diagram for tf2::BufferInterface:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual 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, const ros::Duration timeout, std::string *errstr=NULL) const =0
 Test if a transform is possible.
virtual bool canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout, std::string *errstr=NULL) const =0
 Test if a transform is possible.
virtual
geometry_msgs::TransformStamped 
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, const ros::Duration timeout) const =0
 Get the transform between two frames by frame ID assuming fixed frame.
virtual
geometry_msgs::TransformStamped 
lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const =0
 Get the transform between two frames by frame ID.
template<class A , class B >
B & transform (const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
template<class T >
T & transform (const T &in, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
template<class T >
T & transform (const T &in, T &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
template<class A , class B >
B & transform (const A &in, B &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
template<class T >
transform (const T &in, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
template<class T >
T & transform (const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const

Detailed Description

Definition at line 102 of file buffer_interface.h.


Member Function Documentation

virtual bool tf2::BufferInterface::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,
const ros::Duration  timeout,
std::string *  errstr = NULL 
) const [pure virtual]

Test if a transform is possible.

Parameters:
target_frame The frame into which to transform
target_time The time into which to transform
source_frame The frame from which to transform
source_time The time from which to transform
fixed_frame The frame in which to treat the transform as constant in time
timeout How long to block before failing
errstr A pointer to a string which will be filled with why the transform failed, if not NULL
Returns:
True if the transform is possible, false otherwise

Implemented in tf2::Buffer, and tf2::BufferClient.

virtual bool tf2::BufferInterface::canTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time &  time,
const ros::Duration  timeout,
std::string *  errstr = NULL 
) const [pure virtual]

Test if a transform is possible.

Parameters:
target_frame The frame into which to transform
source_frame The frame from which to transform
time The time at which to transform
timeout How long to block before failing
errstr A pointer to a string which will be filled with why the transform failed, if not NULL
Returns:
True if the transform is possible, false otherwise

Implemented in tf2::Buffer, and tf2::BufferClient.

virtual geometry_msgs::TransformStamped tf2::BufferInterface::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,
const ros::Duration  timeout 
) const [pure virtual]

Get the transform between two frames by frame ID assuming fixed frame.

Parameters:
target_frame The frame to which data should be transformed
target_time The time to which the data should be transformed. (0 will get the latest)
source_frame The frame where the data originated
source_time The time at which the source_frame should be evaluated. (0 will get the latest)
fixed_frame The frame in which to assume the transform is constant in time.
timeout How long to block before failing
Returns:
The transform between the frames

Possible exceptions tf2::LookupException, tf2::ConnectivityException, tf2::ExtrapolationException, tf2::InvalidArgumentException

Implemented in tf2::Buffer, and tf2::BufferClient.

virtual geometry_msgs::TransformStamped tf2::BufferInterface::lookupTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time &  time,
const ros::Duration  timeout 
) const [pure virtual]

Get the transform between two frames by frame ID.

Parameters:
target_frame The frame to which data should be transformed
source_frame The frame where the data originated
time The time at which the value of the transform is desired. (0 will get the latest)
timeout How long to block before failing
Returns:
The transform between the frames

Possible exceptions tf2::LookupException, tf2::ConnectivityException, tf2::ExtrapolationException, tf2::InvalidArgumentException

Implemented in tf2::Buffer, and tf2::BufferClient.

template<class A , class B >
B& tf2::BufferInterface::transform ( const A &  in,
B &  out,
const std::string &  target_frame,
const ros::Time &  target_time,
const std::string &  fixed_frame,
ros::Duration  timeout = ros::Duration(0.0) 
) const [inline]

Definition at line 221 of file buffer_interface.h.

template<class T >
T& tf2::BufferInterface::transform ( const T &  in,
const std::string &  target_frame,
const ros::Time &  target_time,
const std::string &  fixed_frame,
ros::Duration  timeout = ros::Duration(0.0) 
) const [inline]

Definition at line 211 of file buffer_interface.h.

template<class T >
T& tf2::BufferInterface::transform ( const T &  in,
T &  out,
const std::string &  target_frame,
const ros::Time &  target_time,
const std::string &  fixed_frame,
ros::Duration  timeout = ros::Duration(0.0) 
) const [inline]

Definition at line 197 of file buffer_interface.h.

template<class A , class B >
B& tf2::BufferInterface::transform ( const A &  in,
B &  out,
const std::string &  target_frame,
ros::Duration  timeout = ros::Duration(0.0) 
) const [inline]

Definition at line 187 of file buffer_interface.h.

template<class T >
T tf2::BufferInterface::transform ( const T &  in,
const std::string &  target_frame,
ros::Duration  timeout = ros::Duration(0.0) 
) const [inline]

Definition at line 178 of file buffer_interface.h.

template<class T >
T& tf2::BufferInterface::transform ( const T &  in,
T &  out,
const std::string &  target_frame,
ros::Duration  timeout = ros::Duration(0.0) 
) const [inline]

Definition at line 167 of file buffer_interface.h.


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


tf2_ros
Author(s): Wim Meeussen, Eitan Marder-Eppstein
autogenerated on Fri Jan 11 09:59:07 2013