#include <transform_collection.h>
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_ |
This wraps a tf transform listener so it can be used interchangeably with a TransformCollection.
Definition at line 92 of file transform_collection.h.
warehouse_ros::LiveTransformSource::LiveTransformSource | ( | double | timeout = 0 | ) | [inline] |
timeout,: | Maximum timeout |
ros::init must be called before creating an instance
Definition at line 98 of file transform_collection.h.
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.
Definition at line 115 of file transform_collection.h.
boost::shared_ptr<tf::TransformListener> warehouse_ros::LiveTransformSource::tf_ [private] |
Definition at line 116 of file transform_collection.h.
Definition at line 117 of file transform_collection.h.