frame_manager.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
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 /*  Macro to issue warning when using deprecated functions with gcc4 or MSVC7: */
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 // helper class for transforming data into Ogre's world frame (the fixed frame)
00069 // during one frame update, the tf tree stays consistent and queries are cached for speedup
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   // @deprecated "relative" flag is no longer needed.
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   // @return Ogre transform for the given header, relative to the fixed frame
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   // @return Ogre transform for the given header (frame + timestamp) relative to the fixed frame
00096   bool getTransform(const std::string& frame, ros::Time time, Ogre::Vector3& position, Ogre::Quaternion& orientation);
00097 
00098   // transform a pose into the fixed frame
00099   // @param header, pose: input pose (e.g. from a PoseStamped)
00100   // @param position, orientation: output pose relative to fixed frame
00101   // @return success
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   // @deprecated "relative" flag is no longer needed.
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   // transform a pose into the fixed frame
00116   // @param frame, time, pose: input pose
00117   // @param position, orientation: output pose relative to fixed frame
00118   // @return success
00119   bool transform(const std::string& frame, ros::Time time, const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation);
00120 
00121   // will clear the internal cache
00122   void update();
00123 
00124   // find out what went wrong during a transformation
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


rviz_qt
Author(s): Dave Hershberger
autogenerated on Fri Dec 6 2013 20:56:52