Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef TRANSFORM_UTIL_TRANSFORM_MANAGER_H_
00031 #define TRANSFORM_UTIL_TRANSFORM_MANAGER_H_
00032
00033 #include <map>
00034 #include <string>
00035
00036 #include <boost/make_shared.hpp>
00037 #include <boost/shared_ptr.hpp>
00038
00039 #include <tf/transform_datatypes.h>
00040 #include <tf/transform_listener.h>
00041
00042 #include <swri_transform_util/local_xy_util.h>
00043 #include <swri_transform_util/transform.h>
00044 #include <swri_transform_util/transformer.h>
00045
00046 namespace swri_transform_util
00047 {
00048 typedef std::map<std::string, boost::shared_ptr<Transformer> > TransformerMap;
00049 typedef std::map<std::string, TransformerMap> SourceTargetMap;
00050
00062 class TransformManager
00063 {
00064 public:
00065 TransformManager();
00066 ~TransformManager();
00067
00076 void Initialize(boost::shared_ptr<tf::TransformListener> tf
00077 = boost::make_shared<tf::TransformListener>());
00078
00101 bool GetTransform(
00102 const std::string& target_frame,
00103 const std::string& source_frame,
00104 const ros::Time& time,
00105 Transform& transform) const;
00106
00125 bool GetTransform(
00126 const std::string& target_frame,
00127 const std::string& source_frame,
00128 Transform& transform) const;
00129
00142 bool SupportsTransform(
00143 const std::string& target_frame,
00144 const std::string& source_frame) const;
00145
00165 bool GetTransform(
00166 const std::string& target_frame,
00167 const std::string& source_frame,
00168 const ros::Time& time,
00169 tf::StampedTransform& transform) const;
00170
00186 bool GetTransform(
00187 const std::string& target_frame,
00188 const std::string& source_frame,
00189 tf::StampedTransform& transform) const;
00190
00212 bool GetTransform(
00213 const std::string& target_frame,
00214 const std::string& source_frame,
00215 const ros::Time& time,
00216 const ros::Duration& timeout,
00217 tf::StampedTransform& transform) const;
00218
00236 bool GetTransform(
00237 const std::string& target_frame,
00238 const std::string& source_frame,
00239 const ros::Duration& timeout,
00240 tf::StampedTransform& transform) const;
00241
00246 const LocalXyWgs84UtilPtr& LocalXyUtil() const;
00247
00248 private:
00249 boost::shared_ptr<tf::TransformListener> tf_listener_;
00250
00251 LocalXyWgs84UtilPtr local_xy_util_;
00252
00253 SourceTargetMap transformers_;
00254 };
00255 typedef boost::shared_ptr<TransformManager> TransformManagerPtr;
00256 }
00257
00258 #endif // TRANSFORM_UTIL_TRANSFORM_MANAGER_H_