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 <QObject>
00036 
00037 #include <ros/time.h>
00038 
00039 #include <OgreVector3.h>
00040 #include <OgreQuaternion.h>
00041 
00042 #include <boost/thread/mutex.hpp>
00043 
00044 #include <geometry_msgs/Pose.h>
00045 
00046 #include <tf2_ros/message_filter.h>
00047 #include <tf/message_filter.h>
00048 
00049 #include <type_traits>
00050 
00051 #ifndef Q_MOC_RUN
00052 #endif
00053 
00054 #if ROS_VERSION_MINIMUM(1,14,0)
00055 namespace tf2_ros
00056 {
00057 class TransformListener;
00058 }
00059 #else
00060 namespace tf
00061 {
00062 class TransformListener;
00063 }
00064 #endif
00065 
00066 namespace rviz
00067 {
00068 class Display;
00069 
00074 class FrameManager: public QObject
00075 {
00076 Q_OBJECT
00077 public:
00078 
00079  using TransformListener = std::conditional<ROS_VERSION_MINIMUM(1,14,0), tf2_ros::TransformListener, tf::TransformListener>::type;
00080  using FilterFailureReason = std::conditional<ROS_VERSION_MINIMUM(1,14,0), tf2_ros::FilterFailureReason, tf::FilterFailureReason>::type;
00081 #if ROS_VERSION_MINIMUM(1,14,0)
00082  template <class message_type>
00083  using MessageFilter = tf2_ros::MessageFilter<message_type>;
00084 #else
00085  template <class message_type>
00086  using MessageFilter = tf::MessageFilter<message_type>;
00087 #endif
00088 
00089   enum SyncMode {
00090     SyncOff = 0,
00091     SyncExact,
00092     SyncApprox
00093   };
00094 
00098   FrameManager(boost::shared_ptr<TransformListener> tf = boost::shared_ptr<TransformListener>());
00099 
00105   ~FrameManager();
00106 
00111    void setFixedFrame(const std::string& frame);
00112 
00114    void setPause( bool pause );
00115 
00116    bool getPause() { return pause_; }
00117 
00119    void setSyncMode( SyncMode mode );
00120 
00121    SyncMode getSyncMode() { return sync_mode_; }
00122 
00124    void syncTime( ros::Time time );
00125 
00127    ros::Time getTime() { return sync_time_; }
00128 
00134   template<typename Header>
00135   bool getTransform(const Header& header, Ogre::Vector3& position, Ogre::Quaternion& orientation)
00136   {
00137     return getTransform(header.frame_id, header.stamp, position, orientation);
00138   }
00139 
00146   bool getTransform(const std::string& frame, ros::Time time, Ogre::Vector3& position, Ogre::Quaternion& orientation);
00147 
00154   template<typename Header>
00155   bool transform(const Header& header, const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation)
00156   {
00157     return transform(header.frame_id, header.stamp, pose, position, orientation);
00158   }
00159 
00167   bool transform(const std::string& frame, ros::Time time, const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation);
00168 
00170   void update();
00171 
00177   bool frameHasProblems(const std::string& frame, ros::Time time, std::string& error);
00178 
00184   bool transformHasProblems(const std::string& frame, ros::Time time, std::string& error);
00185 
00194   template<class M>
00195   void registerFilterForTransformStatusCheck(MessageFilter<M>* filter, Display* display)
00196   {
00197     filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, _1, display));
00198     filter->registerFailureCallback(boost::bind(&FrameManager::failureCallback<M>, this, _1, _2, display));
00199   }
00200 
00202   const std::string& getFixedFrame() { return fixed_frame_; }
00203 
00205   TransformListener* getTFClient() { return tf_.get(); }
00206 
00208   const boost::shared_ptr<TransformListener>& getTFClientPtr() { return tf_; }
00209 
00219   std::string discoverFailureReason(const std::string& frame_id,
00220                                     const ros::Time& stamp,
00221                                     const std::string& caller_id,
00222                                     FilterFailureReason reason);
00223 
00224 Q_SIGNALS:
00226   void fixedFrameChanged();
00227 
00228 private:
00229 
00230   bool adjustTime( const std::string &frame, ros::Time &time );
00231 
00232   template<class M>
00233   void messageCallback(const ros::MessageEvent<M const>& msg_evt, Display* display)
00234   {
00235     boost::shared_ptr<M const> const &msg = msg_evt.getConstMessage();
00236     std::string authority = msg_evt.getPublisherName();
00237 
00238     messageArrived(msg->info.header.frame_id, msg->info.header.stamp, authority, display);
00239   }
00240 
00241   template<class M>
00242   void failureCallback(const ros::MessageEvent<M const>& msg_evt, FilterFailureReason reason, Display* display)
00243   {
00244     boost::shared_ptr<M const> const &msg = msg_evt.getConstMessage();
00245     std::string authority = msg_evt.getPublisherName();
00246 
00247     messageFailed(msg->info.header.frame_id, msg->info.header.stamp, authority, reason, display);
00248   }
00249 
00250   void messageArrived(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, Display* display);
00251   void messageFailed(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, FilterFailureReason reason, Display* display);
00252 
00253   struct CacheKey
00254   {
00255     CacheKey(const std::string& f, ros::Time t)
00256     : frame(f)
00257     , time(t)
00258     {}
00259 
00260     bool operator<(const CacheKey& rhs) const
00261     {
00262       if (frame != rhs.frame)
00263       {
00264         return frame < rhs.frame;
00265       }
00266 
00267       return time < rhs.time;
00268     }
00269 
00270     std::string frame;
00271     ros::Time time;
00272   };
00273 
00274   struct CacheEntry
00275   {
00276     CacheEntry(const Ogre::Vector3& p, const Ogre::Quaternion& o)
00277     : position(p)
00278     , orientation(o)
00279     {}
00280 
00281     Ogre::Vector3 position;
00282     Ogre::Quaternion orientation;
00283   };
00284   typedef std::map<CacheKey, CacheEntry > M_Cache;
00285 
00286   boost::mutex cache_mutex_;
00287   M_Cache cache_;
00288 
00289   boost::shared_ptr<TransformListener> tf_;
00290   std::string fixed_frame_;
00291 
00292   bool pause_;
00293 
00294   SyncMode sync_mode_;
00295 
00296   // the current synchronized time, used to overwrite ros:Time(0)
00297   ros::Time sync_time_;
00298 
00299   // used for approx. syncing
00300   double sync_delta_;
00301   double current_delta_;
00302 };
00303 
00304 }
00305 
00306 #endif // RVIZ_FRAME_MANAGER_H


grid_map_rviz_plugin
Author(s): Philipp Krüsi, Péter Fankhauser
autogenerated on Tue Jul 9 2019 05:06:44