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 #include <tf2_ros/buffer.h>
39 #include <geometry_msgs/Pose.h>
40 
41 #include <OgreVector3.h>
42 #include <OgreQuaternion.h>
43 
44 #include <boost/thread/mutex.hpp>
45 
46 #ifndef Q_MOC_RUN
47 #include <tf2_ros/message_filter.h>
48 #endif
49 
50 namespace tf2_ros
51 {
52 class TransformListener;
53 }
54 
55 namespace rviz
56 {
57 class Display;
58 
64 class FrameManager : public QObject
65 {
66  Q_OBJECT
67 public:
68  enum SyncMode
69  {
70  SyncOff = 0,
71  SyncExact,
72  SyncApprox
73  };
74 
76  explicit FrameManager(std::shared_ptr<tf2_ros::Buffer> tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
77  std::shared_ptr<tf2_ros::TransformListener> tf_listener =
78  std::shared_ptr<tf2_ros::TransformListener>());
79 
85  ~FrameManager() override;
86 
91  void setFixedFrame(const std::string& frame);
92 
94  void setPause(bool pause);
95 
96  bool getPause()
97  {
98  return pause_;
99  }
100 
102  void setSyncMode(SyncMode mode);
103 
104  SyncMode getSyncMode()
105  {
106  return sync_mode_;
107  }
108 
110  void syncTime(ros::Time time);
111 
113  ros::Time getTime()
114  {
115  return sync_time_;
116  }
117 
123  template <typename Header>
124  bool getTransform(const Header& header, Ogre::Vector3& position, Ogre::Quaternion& orientation)
125  {
126  return getTransform(header.frame_id, header.stamp, position, orientation);
127  }
128 
135  bool getTransform(const std::string& frame,
136  ros::Time time,
137  Ogre::Vector3& position,
138  Ogre::Quaternion& orientation);
139 
146  template <typename Header>
147  bool transform(const Header& header,
148  const geometry_msgs::Pose& pose,
149  Ogre::Vector3& position,
150  Ogre::Quaternion& orientation)
151  {
152  return transform(header.frame_id, header.stamp, pose, position, orientation);
153  }
154 
162  bool transform(const std::string& frame,
163  ros::Time time,
164  const geometry_msgs::Pose& pose,
165  Ogre::Vector3& position,
166  Ogre::Quaternion& orientation);
167 
169  void update();
170 
176  bool frameHasProblems(const std::string& frame, ros::Time time, std::string& error);
177 
183  bool transformHasProblems(const std::string& frame, ros::Time time, std::string& error);
184 
192  template <class M>
193  void registerFilterForTransformStatusCheck(tf2_ros::MessageFilter<M>* filter, Display* display)
194  {
195  filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, _1, display));
196  filter->registerFailureCallback(boost::bind(
197  &FrameManager::failureCallback<M, tf2_ros::FilterFailureReason>, this, _1, _2, display));
198  }
199 
201  const std::string& getFixedFrame()
202  {
203  return fixed_frame_;
204  }
205 
206  const std::shared_ptr<tf2_ros::Buffer> getTF2BufferPtr()
207  {
208  return tf_buffer_;
209  }
210 
220  std::string discoverFailureReason(const std::string& frame_id,
221  const ros::Time& stamp,
222  const std::string& caller_id,
224 
225 Q_SIGNALS:
227  void fixedFrameChanged();
228 
229 private:
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  const std::string& authority = msg_evt.getPublisherName();
237 
238  // the following diverges from original rviz sources (noetic) for backward compatibility
239  messageArrived(msg->info.header.frame_id, msg->info.header.stamp, authority, display);
240  }
241 
242  template <class M, class TfFilterFailureReasonType>
243  void failureCallback(const ros::MessageEvent<M const>& msg_evt,
244  TfFilterFailureReasonType reason,
245  Display* display)
246  {
247  boost::shared_ptr<M const> const& msg = msg_evt.getConstMessage();
248  const std::string& authority = msg_evt.getPublisherName();
249 
250  // the following diverges from original rviz sources (noetic) for backward compatibility
251  messageFailed(msg->info.header.frame_id, msg->info.header.stamp, authority, reason, display);
252  }
253 
254  void messageArrived(const std::string& frame_id,
255  const ros::Time& stamp,
256  const std::string& caller_id,
257  Display* display);
258 
259  void messageFailedImpl(const std::string& caller_id, const std::string& status_text, Display* display);
260 
261  template <class TfFilterFailureReasonType>
262  void messageFailed(const std::string& frame_id,
263  const ros::Time& stamp,
264  const std::string& caller_id,
265  TfFilterFailureReasonType reason,
266  Display* display)
267  {
268  std::string status_text = discoverFailureReason(frame_id, stamp, caller_id, reason);
269  messageFailedImpl(caller_id, status_text, display);
270  }
271 
272  struct CacheKey
273  {
274  CacheKey(const std::string& f, ros::Time t) : frame(f), time(t)
275  {
276  }
277 
278  bool operator<(const CacheKey& rhs) const
279  {
280  if (frame != rhs.frame)
281  {
282  return frame < rhs.frame;
283  }
284 
285  return time < rhs.time;
286  }
287 
288  std::string frame;
289  ros::Time time;
290  };
291 
292  struct CacheEntry
293  {
294  CacheEntry(const Ogre::Vector3& p, const Ogre::Quaternion& o) : position(p), orientation(o)
295  {
296  }
297 
298  Ogre::Vector3 position;
299  Ogre::Quaternion orientation;
300  };
301  typedef std::map<CacheKey, CacheEntry> M_Cache;
302 
303  boost::mutex cache_mutex_;
304  M_Cache cache_;
305 
306  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
307  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
308  std::string fixed_frame_;
309  tf2::CompactFrameID fixed_frame_id_;
310 
311  bool pause_;
312 
313  SyncMode sync_mode_;
314 
315  // the current synchronized time, used to overwrite ros:Time(0)
316  ros::Time sync_time_;
317 
318  // used for approx. syncing
319  double sync_delta_;
320  double current_delta_;
321 };
322 
323 } // namespace rviz
324 
325 #endif // RVIZ_FRAME_MANAGER_H
uint32_t CompactFrameID
message_filters::Connection registerFailureCallback(const FailureCallback &callback)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
const std::string & getPublisherName() const
const boost::shared_ptr< ConstMessage > & getConstMessage() const
ros::Time stamp
Connection registerCallback(const C &callback)


grid_map_rviz_plugin
Author(s): Philipp Krüsi , Péter Fankhauser
autogenerated on Tue Jun 1 2021 02:13:47