Public Member Functions | Private Member Functions | Private Attributes
mongo_ros::TransformCollection Class Reference

#include <transform_collection.h>

Inheritance diagram for mongo_ros::TransformCollection:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual tf::StampedTransform lookupTransform (const std::string &target_frame, const std::string &source_frame, double t) const
 TransformCollection (const std::string &db, const std::string &coll="tf", const std::string &host="localhost", const unsigned port=27017, const double history_length=10.0)

Private Member Functions

mongo::Query transformQuery (double t) const
 Return a query that returns transforms relevant to query at time t.

Private Attributes

MessageCollection< tf::tfMessage > coll_
double history_length_

Detailed Description

The setup is that you have a db containing a collection with tf messages, in which each message has a metadata field named 'stamp', that equals the tf timestamp (this could be generated, e.g., with bag_to_db followed by add_metadata). Given such a collection, this class allows querying for a transform as with tf::TransformListener::lookupTransform, except this is deterministic with no dependency on network state or message queues.

Definition at line 69 of file transform_collection.h.


Constructor & Destructor Documentation

mongo_ros::TransformCollection::TransformCollection ( const std::string &  db,
const std::string &  coll = "tf",
const std::string &  host = "localhost",
const unsigned  port = 27017,
const double  history_length = 10.0 
) [inline]

Definition at line 72 of file transform_collection.h.


Member Function Documentation

tf::StampedTransform mongo_ros::TransformCollection::lookupTransform ( const std::string &  target_frame,
const std::string &  source_frame,
double  t 
) const [virtual]

Get the transform between two frames at a given timepoint. Can throw all the exceptions tf::lookupTransform can.

Implements mongo_ros::TransformSource.

Definition at line 65 of file transform_collection.cpp.

mongo::Query mongo_ros::TransformCollection::transformQuery ( double  t) const [private]

Return a query that returns transforms relevant to query at time t.

Definition at line 55 of file transform_collection.cpp.


Member Data Documentation

Definition at line 94 of file transform_collection.h.

Definition at line 95 of file transform_collection.h.


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


warehouse_ros
Author(s): Bhaskara Marthi
autogenerated on Wed Aug 26 2015 16:44:56