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
00047 #if defined(__GNUC__) && ( __GNUC__ >= 4 )
00048 #define DEPRECATED(x) __attribute__((deprecated)) x
00049 #elif defined(__VISUALC__) && (__VISUALC__ >= 1300)
00050 #define DEPRECATED(x) __declspec(deprecated) x
00051 #else
00052 #define DEPRECATED(x) x
00053 #endif
00054
00055 namespace tf
00056 {
00057 class TransformListener;
00058 }
00059
00060 namespace rviz
00061 {
00062 class Display;
00063
00064 class FrameManager;
00065 typedef boost::shared_ptr<FrameManager> FrameManagerPtr;
00066 typedef boost::weak_ptr<FrameManager> FrameManagerWPtr;
00067
00068
00069
00070 class FrameManager
00071 {
00072 public:
00073 static FrameManagerPtr instance();
00074
00075 FrameManager();
00076 ~FrameManager();
00077
00078 void setFixedFrame(const std::string& frame);
00079
00080
00081 template<typename Header>
00082 __attribute__((deprecated))
00083 bool getTransform(const Header& header, Ogre::Vector3& position, Ogre::Quaternion& orientation, bool relative)
00084 {
00085 return getTransform(header, position, orientation);
00086 }
00087
00088
00089 template<typename Header>
00090 bool getTransform(const Header& header, Ogre::Vector3& position, Ogre::Quaternion& orientation)
00091 {
00092 return getTransform(header.frame_id, header.stamp, position, orientation);
00093 }
00094
00095
00096 bool getTransform(const std::string& frame, ros::Time time, Ogre::Vector3& position, Ogre::Quaternion& orientation);
00097
00098
00099
00100
00101
00102 template<typename Header>
00103 bool transform(const Header& header, const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation)
00104 {
00105 return transform(header.frame_id, header.stamp, pose, position, orientation);
00106 }
00107
00108
00109 __attribute__((deprecated))
00110 bool transform(const std::string& frame, ros::Time time, const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation, bool relative)
00111 {
00112 return transform(frame, time, pose, position, orientation);
00113 }
00114
00115
00116
00117
00118
00119 bool transform(const std::string& frame, ros::Time time, const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation);
00120
00121
00122 void update();
00123
00124
00125 bool frameHasProblems(const std::string& frame, ros::Time time, std::string& error);
00126 bool transformHasProblems(const std::string& frame, ros::Time time, std::string& error);
00127
00128 template<class M>
00129 void registerFilterForTransformStatusCheck(tf::MessageFilter<M>* filter, Display* display)
00130 {
00131 filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, _1, display));
00132 filter->registerFailureCallback(boost::bind(&FrameManager::failureCallback<M>, this, _1, _2, display));
00133 }
00134
00135 const std::string& getFixedFrame() { return fixed_frame_; }
00136 tf::TransformListener* getTFClient() { return tf_; }
00137
00138 std::string discoverFailureReason(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, tf::FilterFailureReason reason);
00139
00140 private:
00141 template<class M>
00142 void messageCallback(const boost::shared_ptr<M const>& msg, Display* display)
00143 {
00144 messageArrived(msg->header.frame_id, msg->header.stamp, msg->__connection_header ? (*msg->__connection_header)["callerid"] : "unknown", display);
00145 }
00146
00147 template<class M>
00148 void failureCallback(const boost::shared_ptr<M const>& msg, tf::FilterFailureReason reason, Display* display)
00149 {
00150 messageFailed(msg->header.frame_id, msg->header.stamp, msg->__connection_header ? (*msg->__connection_header)["callerid"] : "unknown", reason, display);
00151 }
00152
00153 void messageArrived(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, Display* display);
00154 void messageFailed(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, tf::FilterFailureReason reason, Display* display);
00155
00156 struct CacheKey
00157 {
00158 CacheKey(const std::string& f, ros::Time t)
00159 : frame(f)
00160 , time(t)
00161 {}
00162
00163 bool operator<(const CacheKey& rhs) const
00164 {
00165 if (frame != rhs.frame)
00166 {
00167 return frame < rhs.frame;
00168 }
00169
00170 return time < rhs.time;
00171 }
00172
00173 std::string frame;
00174 ros::Time time;
00175 };
00176
00177 struct CacheEntry
00178 {
00179 CacheEntry(const Ogre::Vector3& p, const Ogre::Quaternion& o)
00180 : position(p)
00181 , orientation(o)
00182 {}
00183
00184 Ogre::Vector3 position;
00185 Ogre::Quaternion orientation;
00186 };
00187 typedef std::map<CacheKey, CacheEntry > M_Cache;
00188
00189 boost::mutex cache_mutex_;
00190 M_Cache cache_;
00191
00192 tf::TransformListener* tf_;
00193 std::string fixed_frame_;
00194 };
00195
00196 }
00197
00198 #endif // RVIZ_FRAME_MANAGER_H