Public Member Functions
tf2_ros::BufferInterface Class Reference

#include <buffer_interface.h>

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

List of all members.

Public Member Functions

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 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
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.
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.
template<class T >
T & transform (const T &in, T &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 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 >
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 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 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

Detailed Description

Definition at line 47 of file buffer_interface.h.


Member Function Documentation

virtual bool tf2_ros::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_frameThe frame into which to transform
source_frameThe frame from which to transform
timeThe time at which to transform
timeoutHow long to block before failing
errstrA 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_ros::Buffer, and tf2_ros::BufferClient.

virtual bool tf2_ros::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_frameThe frame into which to transform
target_timeThe time into which to transform
source_frameThe frame from which to transform
source_timeThe time from which to transform
fixed_frameThe frame in which to treat the transform as constant in time
timeoutHow long to block before failing
errstrA 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_ros::Buffer, and tf2_ros::BufferClient.

virtual geometry_msgs::TransformStamped tf2_ros::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_frameThe frame to which data should be transformed
source_frameThe frame where the data originated
timeThe time at which the value of the transform is desired. (0 will get the latest)
timeoutHow long to block before failing
Returns:
The transform between the frames

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

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

virtual geometry_msgs::TransformStamped tf2_ros::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_frameThe frame to which data should be transformed
target_timeThe time to which the data should be transformed. (0 will get the latest)
source_frameThe frame where the data originated
source_timeThe time at which the source_frame should be evaluated. (0 will get the latest)
fixed_frameThe frame in which to assume the transform is constant in time.
timeoutHow long to block before failing
Returns:
The transform between the frames

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

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

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

Definition at line 112 of file buffer_interface.h.

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

Definition at line 123 of file buffer_interface.h.

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

Definition at line 132 of file buffer_interface.h.

template<class T >
T& tf2_ros::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 142 of file buffer_interface.h.

template<class T >
T tf2_ros::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 156 of file buffer_interface.h.

template<class A , class B >
B& tf2_ros::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 166 of file buffer_interface.h.


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


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Aug 27 2015 13:10:05