frame_manager.cpp
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 #include "frame_manager.h"
31 #include "display.h"
32 #include "properties/property.h"
33 
34 #include <tf/transform_listener.h>
35 #include <ros/ros.h>
36 
37 #include <std_msgs/Float32.h>
38 
39 namespace rviz
40 {
41 // TODO(wjwwood): remove this when deprecated interface is removed
42 #ifndef _WIN32
43 #pragma GCC diagnostic push
44 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
45 #endif
46 
47 FrameManager::FrameManager() : FrameManager(boost::shared_ptr<tf::TransformListener>())
48 {
49 }
50 
51 #ifndef _WIN32
52 #pragma GCC diagnostic pop
53 #endif
54 
56 {
57  if (!tf)
58  tf_.reset(new tf::TransformListener(ros::NodeHandle(), ros::Duration(10 * 60), true));
59  else
60  tf_ = tf;
61 
63  setPause(false);
64 }
65 
67 {
68 }
69 
71 {
72  boost::mutex::scoped_lock lock(cache_mutex_);
73  if (!pause_)
74  {
75  cache_.clear();
76  }
77 
78  if (!pause_)
79  {
80  switch (sync_mode_)
81  {
82  case SyncOff:
84  break;
85  case SyncExact:
86  break;
87  case SyncApprox:
88  // adjust current time offset to sync source
90  try
91  {
93  }
94  catch (...)
95  {
97  }
98  break;
99  }
100  }
101 }
102 
103 void FrameManager::setFixedFrame(const std::string& frame)
104 {
105  bool should_emit = false;
106  {
107  boost::mutex::scoped_lock lock(cache_mutex_);
108  if (fixed_frame_ != frame)
109  {
110  fixed_frame_ = frame;
111  cache_.clear();
112  should_emit = true;
113  }
114  }
115  if (should_emit)
116  {
117  // This emission must be kept outside of the mutex lock to avoid deadlocks.
118  Q_EMIT fixedFrameChanged();
119  }
120 }
121 
122 void FrameManager::setPause(bool pause)
123 {
124  pause_ = pause;
125 }
126 
128 {
129  sync_mode_ = mode;
130  sync_time_ = ros::Time(0);
131  current_delta_ = 0;
132  sync_delta_ = 0;
133 }
134 
136 {
137  switch (sync_mode_)
138  {
139  case SyncOff:
140  break;
141  case SyncExact:
142  sync_time_ = time;
143  break;
144  case SyncApprox:
145  if (time == ros::Time(0))
146  {
147  sync_delta_ = 0;
148  return;
149  }
150  // avoid exception due to negative time
151  if (ros::Time::now() >= time)
152  {
153  sync_delta_ = (ros::Time::now() - time).toSec();
154  }
155  else
156  {
158  }
159  break;
160  }
161 }
162 
163 bool FrameManager::adjustTime(const std::string& frame, ros::Time& time)
164 {
165  // we only need to act if we get a zero timestamp, which means "latest"
166  if (time != ros::Time())
167  {
168  return true;
169  }
170 
171  switch (sync_mode_)
172  {
173  case SyncOff:
174  break;
175  case SyncExact:
176  time = sync_time_;
177  break;
178  case SyncApprox:
179  {
180  // if we don't have tf info for the given timestamp, use the latest available
181  ros::Time latest_time;
182  std::string error_string;
183  int error_code;
184  error_code = tf_->getLatestCommonTime(fixed_frame_, frame, latest_time, &error_string);
185 
186  if (error_code != 0)
187  {
188  ROS_ERROR("Error getting latest time from frame '%s' to frame '%s': %s (Error code: %d)",
189  frame.c_str(), fixed_frame_.c_str(), error_string.c_str(), error_code);
190  return false;
191  }
192 
193  if (latest_time > sync_time_)
194  {
195  time = sync_time_;
196  }
197  }
198  break;
199  }
200  return true;
201 }
202 
203 
204 bool FrameManager::getTransform(const std::string& frame,
205  ros::Time time,
206  Ogre::Vector3& position,
207  Ogre::Quaternion& orientation)
208 {
209  if (!adjustTime(frame, time))
210  {
211  return false;
212  }
213 
214  boost::mutex::scoped_lock lock(cache_mutex_);
215 
216  position = Ogre::Vector3(9999999, 9999999, 9999999);
217  orientation = Ogre::Quaternion::IDENTITY;
218 
219  if (fixed_frame_.empty())
220  {
221  return false;
222  }
223 
224  M_Cache::iterator it = cache_.find(CacheKey(frame, time));
225  if (it != cache_.end())
226  {
227  position = it->second.position;
228  orientation = it->second.orientation;
229  return true;
230  }
231 
232  geometry_msgs::Pose pose;
233  pose.orientation.w = 1.0f;
234 
235  if (!transform(frame, time, pose, position, orientation))
236  {
237  return false;
238  }
239 
240  cache_.insert(std::make_pair(CacheKey(frame, time), CacheEntry(position, orientation)));
241 
242  return true;
243 }
244 
245 bool FrameManager::transform(const std::string& frame,
246  ros::Time time,
247  const geometry_msgs::Pose& pose_msg,
248  Ogre::Vector3& position,
249  Ogre::Quaternion& orientation)
250 {
251  if (!adjustTime(frame, time))
252  {
253  return false;
254  }
255 
256  position = Ogre::Vector3::ZERO;
257  orientation = Ogre::Quaternion::IDENTITY;
258 
259  // put all pose data into a tf stamped pose
260  tf::Quaternion bt_orientation(pose_msg.orientation.x, pose_msg.orientation.y, pose_msg.orientation.z,
261  pose_msg.orientation.w);
262  tf::Vector3 bt_position(pose_msg.position.x, pose_msg.position.y, pose_msg.position.z);
263 
264  if (bt_orientation.x() == 0.0 && bt_orientation.y() == 0.0 && bt_orientation.z() == 0.0 &&
265  bt_orientation.w() == 0.0)
266  {
267  bt_orientation.setW(1.0);
268  }
269 
270  tf::Stamped<tf::Pose> pose_in(tf::Transform(bt_orientation, bt_position), time, frame);
271  tf::Stamped<tf::Pose> pose_out;
272 
273  // convert pose into new frame
274  try
275  {
276  tf_->transformPose(fixed_frame_, pose_in, pose_out);
277  }
278  catch (std::runtime_error& e)
279  {
280  ROS_DEBUG("Error transforming from frame '%s' to frame '%s': %s", frame.c_str(),
281  fixed_frame_.c_str(), e.what());
282  return false;
283  }
284 
285  bt_position = pose_out.getOrigin();
286  position = Ogre::Vector3(bt_position.x(), bt_position.y(), bt_position.z());
287 
288  bt_orientation = pose_out.getRotation();
289  orientation =
290  Ogre::Quaternion(bt_orientation.w(), bt_orientation.x(), bt_orientation.y(), bt_orientation.z());
291 
292  return true;
293 }
294 
295 bool FrameManager::frameHasProblems(const std::string& frame, ros::Time /*time*/, std::string& error)
296 {
297  if (!tf_->frameExists(frame))
298  {
299  error = "Frame [" + frame + "] does not exist";
300  if (frame == fixed_frame_)
301  {
302  error = "Fixed " + error;
303  }
304  return true;
305  }
306 
307  return false;
308 }
309 
310 bool FrameManager::transformHasProblems(const std::string& frame, ros::Time time, std::string& error)
311 {
312  if (!adjustTime(frame, time))
313  {
314  return false;
315  }
316 
317  std::string tf_error;
318  bool transform_succeeded = tf_->canTransform(fixed_frame_, frame, time, &tf_error);
319  if (transform_succeeded)
320  {
321  return false;
322  }
323 
324  bool ok = true;
325  ok = ok && !frameHasProblems(fixed_frame_, time, error);
326  ok = ok && !frameHasProblems(frame, time, error);
327 
328  if (ok)
329  {
330  std::stringstream ss;
331  ss << "No transform to fixed frame [" << fixed_frame_ << "]. TF error: [" << tf_error << "]";
332  error = ss.str();
333  ok = false;
334  }
335 
336  {
337  std::stringstream ss;
338  ss << "For frame [" << frame << "]: " << error;
339  error = ss.str();
340  }
341 
342  return !ok;
343 }
344 
345 std::string getTransformStatusName(const std::string& caller_id)
346 {
347  std::stringstream ss;
348  ss << "Transform [sender=" << caller_id << "]";
349  return ss.str();
350 }
351 
352 std::string FrameManager::discoverFailureReason(const std::string& frame_id,
353  const ros::Time& stamp,
354  const std::string& /*caller_id*/,
356 {
358  {
359  std::stringstream ss;
360  ss << "Message removed because it is too old (frame=[" << frame_id << "], stamp=[" << stamp << "])";
361  return ss.str();
362  }
363  else
364  {
365  std::string error;
366  if (transformHasProblems(frame_id, stamp, error))
367  {
368  return error;
369  }
370  }
371 
372  return "Unknown reason for transform failure";
373 }
374 
375 std::string FrameManager::discoverFailureReason(const std::string& frame_id,
376  const ros::Time& stamp,
377  const std::string& /*caller_id*/,
379 {
381  {
382  std::stringstream ss;
383  ss << "Message removed because it is too old (frame=[" << frame_id << "], stamp=[" << stamp << "])";
384  return ss.str();
385  }
386  else
387  {
388  std::string error;
389  if (transformHasProblems(frame_id, stamp, error))
390  {
391  return error;
392  }
393  }
394 
395  return "Unknown reason for transform failure (frame=[" + frame_id + "])";
396 }
397 
398 void FrameManager::messageArrived(const std::string& /*frame_id*/,
399  const ros::Time& /*stamp*/,
400  const std::string& caller_id,
401  Display* display)
402 {
403  display->setStatusStd(StatusProperty::Ok, getTransformStatusName(caller_id), "Transform OK");
404 }
405 
406 void FrameManager::messageFailedImpl(const std::string& caller_id,
407  const std::string& status_text,
408  Display* display)
409 {
410  std::string status_name = getTransformStatusName(caller_id);
411 
412  display->setStatusStd(StatusProperty::Error, status_name, status_text);
413 }
414 
415 } // namespace rviz
bool adjustTime(const std::string &frame, ros::Time &time)
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
Show status level and text, using a std::string. Convenience function which converts std::string to Q...
Definition: display.h:163
std::string discoverFailureReason(const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, tf::FilterFailureReason reason)
Create a description of a transform problem.
bool transformHasProblems(const std::string &frame, ros::Time time, std::string &error)
Check to see if a transform is known between a given frame and the fixed frame.
std::string getTransformStatusName(const std::string &caller_id)
boost::mutex cache_mutex_
void update()
Clear the internal cache.
void messageArrived(const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, Display *display)
boost::shared_ptr< tf::TransformListener > tf_
void messageFailedImpl(const std::string &caller_id, const std::string &status_text, Display *display)
FrameManager()
Default constructor, which will create a tf::TransformListener automatically.
Helper class for transforming data into Ogre&#39;s world frame (the fixed frame).
Definition: frame_manager.h:70
~FrameManager() override
Destructor.
ROSCPP_DECL bool ok()
bool transform(const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Transform a pose from a frame into the fixed frame.
void setPause(bool pause)
Enable/disable pause mode.
std::string fixed_frame_
void syncTime(ros::Time time)
Synchronize with given time.
void setFixedFrame(const std::string &frame)
Set the frame to consider "fixed", into which incoming data is transformed.
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Return the pose for a header, relative to the fixed frame, in Ogre classes.
bool frameHasProblems(const std::string &frame, ros::Time time, std::string &error)
Check to see if a frame exists in the tf::TransformListener.
void setSyncMode(SyncMode mode)
Set synchronization mode (off/exact/approximate)
void fixedFrameChanged()
Emitted whenever the fixed frame changes.
static Time now()
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:24