frame_manager.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef RVIZ_FRAME_MANAGER_H
31 #define RVIZ_FRAME_MANAGER_H
32 
33 #include <map>
34 
35 #include <QObject>
36 
37 #include <ros/time.h>
38 
39 #include <OgreVector3.h>
40 #include <OgreQuaternion.h>
41 
42 #include <boost/thread/mutex.hpp>
43 
44 #include <geometry_msgs/Pose.h>
45 
46 #include <tf2_ros/message_filter.h>
47 #include <tf/message_filter.h>
48 
49 #include <type_traits>
50 
51 #ifndef Q_MOC_RUN
52 #endif
53 
54 #if ROS_VERSION_MINIMUM(1,14,0)
55 namespace tf2_ros
56 {
57 class TransformListener;
58 }
59 #else
60 namespace tf
61 {
62 class TransformListener;
63 }
64 #endif
65 
66 namespace rviz
67 {
68 class Display;
69 
74 class FrameManager: public QObject
75 {
76 Q_OBJECT
77 public:
78 
79  using TransformListener = std::conditional<ROS_VERSION_MINIMUM(1,14,0), tf2_ros::TransformListener, tf::TransformListener>::type;
80  using FilterFailureReason = std::conditional<ROS_VERSION_MINIMUM(1,14,0), tf2_ros::FilterFailureReason, tf::FilterFailureReason>::type;
81 #if ROS_VERSION_MINIMUM(1,14,0)
82  template <class message_type>
83  using MessageFilter = tf2_ros::MessageFilter<message_type>;
84 #else
85  template <class message_type>
86  using MessageFilter = tf::MessageFilter<message_type>;
87 #endif
88 
89  enum SyncMode {
90  SyncOff = 0,
91  SyncExact,
92  SyncApprox
93  };
94 
99 
105  ~FrameManager();
106 
111  void setFixedFrame(const std::string& frame);
112 
114  void setPause( bool pause );
115 
116  bool getPause() { return pause_; }
117 
119  void setSyncMode( SyncMode mode );
120 
121  SyncMode getSyncMode() { return sync_mode_; }
122 
124  void syncTime( ros::Time time );
125 
127  ros::Time getTime() { return sync_time_; }
128 
134  template<typename Header>
135  bool getTransform(const Header& header, Ogre::Vector3& position, Ogre::Quaternion& orientation)
136  {
137  return getTransform(header.frame_id, header.stamp, position, orientation);
138  }
139 
146  bool getTransform(const std::string& frame, ros::Time time, Ogre::Vector3& position, Ogre::Quaternion& orientation);
147 
154  template<typename Header>
155  bool transform(const Header& header, const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation)
156  {
157  return transform(header.frame_id, header.stamp, pose, position, orientation);
158  }
159 
167  bool transform(const std::string& frame, ros::Time time, const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation);
168 
170  void update();
171 
177  bool frameHasProblems(const std::string& frame, ros::Time time, std::string& error);
178 
184  bool transformHasProblems(const std::string& frame, ros::Time time, std::string& error);
185 
194  template<class M>
195  void registerFilterForTransformStatusCheck(MessageFilter<M>* filter, Display* display)
196  {
197  filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, _1, display));
198  filter->registerFailureCallback(boost::bind(&FrameManager::failureCallback<M>, this, _1, _2, display));
199  }
200 
202  const std::string& getFixedFrame() { return fixed_frame_; }
203 
205  TransformListener* getTFClient() { return tf_.get(); }
206 
208  const boost::shared_ptr<TransformListener>& getTFClientPtr() { return tf_; }
209 
219  std::string discoverFailureReason(const std::string& frame_id,
220  const ros::Time& stamp,
221  const std::string& caller_id,
222  FilterFailureReason reason);
223 
224 Q_SIGNALS:
226  void fixedFrameChanged();
227 
228 private:
229 
230  bool adjustTime( const std::string &frame, ros::Time &time );
231 
232  template<class M>
233  void messageCallback(const ros::MessageEvent<M const>& msg_evt, Display* display)
234  {
235  boost::shared_ptr<M const> const &msg = msg_evt.getConstMessage();
236  std::string authority = msg_evt.getPublisherName();
237 
238  messageArrived(msg->info.header.frame_id, msg->info.header.stamp, authority, display);
239  }
240 
241  template<class M>
242  void failureCallback(const ros::MessageEvent<M const>& msg_evt, FilterFailureReason reason, Display* display)
243  {
244  boost::shared_ptr<M const> const &msg = msg_evt.getConstMessage();
245  std::string authority = msg_evt.getPublisherName();
246 
247  messageFailed(msg->info.header.frame_id, msg->info.header.stamp, authority, reason, display);
248  }
249 
250  void messageArrived(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, Display* display);
251  void messageFailed(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, FilterFailureReason reason, Display* display);
252 
253  struct CacheKey
254  {
255  CacheKey(const std::string& f, ros::Time t)
256  : frame(f)
257  , time(t)
258  {}
259 
260  bool operator<(const CacheKey& rhs) const
261  {
262  if (frame != rhs.frame)
263  {
264  return frame < rhs.frame;
265  }
266 
267  return time < rhs.time;
268  }
269 
270  std::string frame;
271  ros::Time time;
272  };
273 
274  struct CacheEntry
275  {
276  CacheEntry(const Ogre::Vector3& p, const Ogre::Quaternion& o)
277  : position(p)
278  , orientation(o)
279  {}
280 
281  Ogre::Vector3 position;
282  Ogre::Quaternion orientation;
283  };
284  typedef std::map<CacheKey, CacheEntry > M_Cache;
285 
286  boost::mutex cache_mutex_;
287  M_Cache cache_;
288 
290  std::string fixed_frame_;
291 
292  bool pause_;
293 
294  SyncMode sync_mode_;
295 
296  // the current synchronized time, used to overwrite ros:Time(0)
297  ros::Time sync_time_;
298 
299  // used for approx. syncing
300  double sync_delta_;
301  double current_delta_;
302 };
303 
304 }
305 
306 #endif // RVIZ_FRAME_MANAGER_H
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
const std::string & getPublisherName() const
const boost::shared_ptr< ConstMessage > & getConstMessage() const
FilterFailureReason
ros::Time stamp


grid_map_rviz_plugin
Author(s): Philipp Krüsi, Péter Fankhauser
autogenerated on Tue Jun 25 2019 20:02:28