Class TransformCollection
- Defined in File transform_collection.h 
Inheritance Relationships
Base Type
- public warehouse_ros::TransformSource(Class TransformSource)
Class Documentation
- 
class TransformCollection : public warehouse_ros::TransformSource
- 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. - Public Functions - 
inline TransformCollection(MessageCollection<tf2_msgs::msg::TFMessage> &coll, const double search_back = 10.0, const double search_forward = 1.0)
 - 
virtual geometry_msgs::msg::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, double t) const override
- Get the transform between two frames at a given timepoint. Can throw all the exceptions tf::lookupTransform can. 
 - 
void putTransform(geometry_msgs::msg::TransformStamped)
- Put the transform into the collection. 
 
- 
inline TransformCollection(MessageCollection<tf2_msgs::msg::TFMessage> &coll, const double search_back = 10.0, const double search_forward = 1.0)