Public Member Functions | Private Attributes
warehouse_ros::LiveTransformSource Class Reference

#include <transform_collection.h>

Inheritance diagram for warehouse_ros::LiveTransformSource:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 LiveTransformSource (double timeout=0)
virtual tf::StampedTransform lookupTransform (const std::string &target, const std::string &source, double t) const

Private Attributes

ros::NodeHandle nh_
boost::shared_ptr
< tf::TransformListener
tf_
ros::Duration timeout_

Detailed Description

This wraps a tf transform listener so it can be used interchangeably with a TransformCollection.

Definition at line 92 of file transform_collection.h.


Constructor & Destructor Documentation

Parameters:
timeout,:Maximum timeout

ros::init must be called before creating an instance

Definition at line 98 of file transform_collection.h.


Member Function Documentation

virtual tf::StampedTransform warehouse_ros::LiveTransformSource::lookupTransform ( const std::string &  target,
const std::string &  source,
double  t 
) const [inline, virtual]

Will return the transform if it becomes available before the timeout expires, else throw a tf exception

Implements warehouse_ros::TransformSource.

Definition at line 105 of file transform_collection.h.


Member Data Documentation

Definition at line 115 of file transform_collection.h.

Definition at line 116 of file transform_collection.h.

Definition at line 117 of file transform_collection.h.


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


warehouse_ros
Author(s): Bhaskara Marthi , Connor Brew
autogenerated on Thu Jun 23 2016 05:36:41