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 RVIZ_FRAME_MANAGER_H
00031 #define RVIZ_FRAME_MANAGER_H
00032
00033 #include <map>
00034
00035 #include <ros/time.h>
00036
00037 #include <OGRE/OgreVector3.h>
00038 #include <OGRE/OgreQuaternion.h>
00039
00040 #include <boost/thread/mutex.hpp>
00041
00042 #include <geometry_msgs/Pose.h>
00043
00044 #include <tf/message_filter.h>
00045
00046 namespace tf
00047 {
00048 class TransformListener;
00049 }
00050
00051 namespace rviz
00052 {
00053 class Display;
00054
00055 class FrameManager;
00056 typedef boost::shared_ptr<FrameManager> FrameManagerPtr;
00057 typedef boost::weak_ptr<FrameManager> FrameManagerWPtr;
00058
00059 class FrameManager
00060 {
00061 public:
00062 static FrameManagerPtr instance();
00063
00064 FrameManager();
00065 ~FrameManager();
00066
00067 void setFixedFrame(const std::string& frame);
00068
00069 template<typename Header>
00070 bool getTransform(const Header& header, Ogre::Vector3& position, Ogre::Quaternion& orientation, bool relative_orientation)
00071 {
00072 return getTransform(header.frame_id, header.stamp, position, orientation, relative_orientation);
00073 }
00074
00075 bool getTransform(const std::string& frame, ros::Time time, Ogre::Vector3& position, Ogre::Quaternion& orientation, bool relative_orientation);
00076
00077 template<typename Header>
00078 bool transform(const Header& header, const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation, bool relative_orientation)
00079 {
00080 return transform(header.frame_id, header.stamp, pose, position, orientation, relative_orientation);
00081 }
00082
00083 bool transform(const std::string& frame, ros::Time time, const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation, bool relative_orientation);
00084 void update();
00085
00086 bool frameHasProblems(const std::string& frame, ros::Time time, std::string& error);
00087 bool transformHasProblems(const std::string& frame, ros::Time time, std::string& error);
00088
00089 template<class M>
00090 void registerFilterForTransformStatusCheck(tf::MessageFilter<M>& filter, Display* display)
00091 {
00092 filter.registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, _1, display));
00093 filter.registerFailureCallback(boost::bind(&FrameManager::failureCallback<M>, this, _1, _2, display));
00094 }
00095
00096 const std::string& getFixedFrame() { return fixed_frame_; }
00097 tf::TransformListener* getTFClient() { return tf_; }
00098
00099 std::string discoverFailureReason(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, tf::FilterFailureReason reason);
00100
00101 private:
00102 template<class M>
00103 void messageCallback(const boost::shared_ptr<M const>& msg, Display* display)
00104 {
00105 messageArrived(msg->header.frame_id, msg->header.stamp, msg->__connection_header ? (*msg->__connection_header)["callerid"] : "unknown", display);
00106 }
00107
00108 template<class M>
00109 void failureCallback(const boost::shared_ptr<M const>& msg, tf::FilterFailureReason reason, Display* display)
00110 {
00111 messageFailed(msg->header.frame_id, msg->header.stamp, msg->__connection_header ? (*msg->__connection_header)["callerid"] : "unknown", reason, display);
00112 }
00113
00114 void messageArrived(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, Display* display);
00115 void messageFailed(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, tf::FilterFailureReason reason, Display* display);
00116
00117 struct CacheKey
00118 {
00119 CacheKey(const std::string& f, ros::Time t, bool r)
00120 : frame(f)
00121 , time(t)
00122 , relative(r)
00123 {}
00124
00125 bool operator<(const CacheKey& rhs) const
00126 {
00127 if (frame != rhs.frame)
00128 {
00129 return frame < rhs.frame;
00130 }
00131
00132 if (time != rhs.time)
00133 {
00134 return time < rhs.time;
00135 }
00136
00137 return relative < rhs.relative;
00138 }
00139
00140 std::string frame;
00141 ros::Time time;
00142 bool relative;
00143 };
00144 struct CacheEntry
00145 {
00146 CacheEntry(const Ogre::Vector3& p, const Ogre::Quaternion& o)
00147 : position(p)
00148 , orientation(o)
00149 {}
00150
00151 Ogre::Vector3 position;
00152 Ogre::Quaternion orientation;
00153 };
00154 typedef std::map<CacheKey, CacheEntry > M_Cache;
00155
00156 boost::mutex cache_mutex_;
00157 M_Cache cache_;
00158
00159 tf::TransformListener* tf_;
00160 std::string fixed_frame_;
00161 };
00162
00163 }
00164
00165 #endif // RVIZ_FRAME_MANAGER_H