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 <QObject>
00036
00037 #include <ros/time.h>
00038
00039 #include <OGRE/OgreVector3.h>
00040 #include <OGRE/OgreQuaternion.h>
00041
00042 #include <boost/thread/mutex.hpp>
00043
00044 #include <geometry_msgs/Pose.h>
00045
00046 #ifndef Q_MOC_RUN
00047 #include <tf/message_filter.h>
00048 #endif
00049
00050 namespace tf
00051 {
00052 class TransformListener;
00053 }
00054
00055 namespace rviz
00056 {
00057 class Display;
00058
00063 class FrameManager: public QObject
00064 {
00065 Q_OBJECT
00066 public:
00067
00068 enum SyncMode {
00069 SyncOff = 0,
00070 SyncExact,
00071 SyncApprox
00072 };
00073
00074 FrameManager();
00075
00081 ~FrameManager();
00082
00087 void setFixedFrame(const std::string& frame);
00088
00090 void setPause( bool pause );
00091
00092 bool getPause() { return pause_; }
00093
00095 void setSyncMode( SyncMode mode );
00096
00097 SyncMode getSyncMode() { return sync_mode_; }
00098
00100 void syncTime( ros::Time time );
00101
00103 ros::Time getTime() { return sync_time_; }
00104
00110 template<typename Header>
00111 bool getTransform(const Header& header, Ogre::Vector3& position, Ogre::Quaternion& orientation)
00112 {
00113 return getTransform(header.frame_id, header.stamp, position, orientation);
00114 }
00115
00122 bool getTransform(const std::string& frame, ros::Time time, Ogre::Vector3& position, Ogre::Quaternion& orientation);
00123
00130 template<typename Header>
00131 bool transform(const Header& header, const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation)
00132 {
00133 return transform(header.frame_id, header.stamp, pose, position, orientation);
00134 }
00135
00143 bool transform(const std::string& frame, ros::Time time, const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation);
00144
00146 void update();
00147
00153 bool frameHasProblems(const std::string& frame, ros::Time time, std::string& error);
00154
00160 bool transformHasProblems(const std::string& frame, ros::Time time, std::string& error);
00161
00170 template<class M>
00171 void registerFilterForTransformStatusCheck(tf::MessageFilter<M>* filter, Display* display)
00172 {
00173 filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, _1, display));
00174 filter->registerFailureCallback(boost::bind(&FrameManager::failureCallback<M>, this, _1, _2, display));
00175 }
00176
00178 const std::string& getFixedFrame() { return fixed_frame_; }
00179
00181 tf::TransformListener* getTFClient() { return tf_.get(); }
00182
00184 const boost::shared_ptr<tf::TransformListener>& getTFClientPtr() { return tf_; }
00185
00195 std::string discoverFailureReason(const std::string& frame_id,
00196 const ros::Time& stamp,
00197 const std::string& caller_id,
00198 tf::FilterFailureReason reason);
00199
00200 Q_SIGNALS:
00202 void fixedFrameChanged();
00203
00204 private:
00205
00206 bool adjustTime( const std::string &frame, ros::Time &time );
00207
00208 template<class M>
00209 void messageCallback(const boost::shared_ptr<M const>& msg, Display* display)
00210 {
00211 messageArrived(msg->header.frame_id, msg->header.stamp, msg->__connection_header ? (*msg->__connection_header)["callerid"] : "unknown", display);
00212 }
00213
00214 template<class M>
00215 void failureCallback(const boost::shared_ptr<M const>& msg, tf::FilterFailureReason reason, Display* display)
00216 {
00217 messageFailed(msg->header.frame_id, msg->header.stamp, msg->__connection_header ? (*msg->__connection_header)["callerid"] : "unknown", reason, display);
00218 }
00219
00220 void messageArrived(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, Display* display);
00221 void messageFailed(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, tf::FilterFailureReason reason, Display* display);
00222
00223 struct CacheKey
00224 {
00225 CacheKey(const std::string& f, ros::Time t)
00226 : frame(f)
00227 , time(t)
00228 {}
00229
00230 bool operator<(const CacheKey& rhs) const
00231 {
00232 if (frame != rhs.frame)
00233 {
00234 return frame < rhs.frame;
00235 }
00236
00237 return time < rhs.time;
00238 }
00239
00240 std::string frame;
00241 ros::Time time;
00242 };
00243
00244 struct CacheEntry
00245 {
00246 CacheEntry(const Ogre::Vector3& p, const Ogre::Quaternion& o)
00247 : position(p)
00248 , orientation(o)
00249 {}
00250
00251 Ogre::Vector3 position;
00252 Ogre::Quaternion orientation;
00253 };
00254 typedef std::map<CacheKey, CacheEntry > M_Cache;
00255
00256 boost::mutex cache_mutex_;
00257 M_Cache cache_;
00258
00259 boost::shared_ptr<tf::TransformListener> tf_;
00260 std::string fixed_frame_;
00261
00262 bool pause_;
00263
00264 SyncMode sync_mode_;
00265
00266
00267 ros::Time sync_time_;
00268
00269
00270 double sync_delta_;
00271 double current_delta_;
00272 };
00273
00274 }
00275
00276 #endif // RVIZ_FRAME_MANAGER_H