tf.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, 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 
32 #ifndef TF_TF_H
33 #define TF_TF_H
34 
35 #include <iostream>
36 #include <iomanip>
37 #include <cmath>
38 #include <vector>
39 #include <sstream>
40 #include <map>
41 
42 #include <tf/exceptions.h>
43 #include "tf/time_cache.h"
44 #include <boost/unordered_map.hpp>
45 #include <boost/signals2.hpp>
46 #include "geometry_msgs/TwistStamped.h"
47 
48 #include <tf2_ros/buffer.h>
49 
50 namespace tf
51 {
53 std::string resolve(const std::string& prefix, const std::string& frame_name);
54 
56 std::string strip_leading_slash(const std::string& frame_name);
57 
59 __attribute__((deprecated)) static inline std::string remap(const std::string& prefix, const std::string& frame_name) { return tf::resolve(prefix, frame_name);} ;
60 
62 
66 typedef struct
67 {
68  std::vector<TransformStorage > inverseTransforms;
69  std::vector<TransformStorage > forwardTransforms;
71 
91 {
92 public:
93  /************* Constants ***********************/
94  static const unsigned int MAX_GRAPH_DEPTH = 100UL;
95  static const double DEFAULT_CACHE_TIME;
96  static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0ULL;
97 
98 
104  Transformer(bool interpolating = true,
105  ros::Duration cache_time_ = ros::Duration(DEFAULT_CACHE_TIME));
106  virtual ~Transformer(void);
107 
109  void clear();
110 
116  bool setTransform(const StampedTransform& transform, const std::string & authority = "default_authority");
117 
118  /*********** Accessors *************/
119 
129  void lookupTransform(const std::string& target_frame, const std::string& source_frame,
130  const ros::Time& time, StampedTransform& transform) const;
142  void lookupTransform(const std::string& target_frame, const ros::Time& target_time,
143  const std::string& source_frame, const ros::Time& source_time,
144  const std::string& fixed_frame, StampedTransform& transform) const;
145 
166  void lookupTwist(const std::string& tracking_frame, const std::string& observation_frame, const std::string& reference_frame,
167  const tf::Point & reference_point, const std::string& reference_point_frame,
168  const ros::Time& time, const ros::Duration& averaging_interval,
169  geometry_msgs::Twist& twist) const;
170 
181  void lookupTwist(const std::string& tracking_frame, const std::string& observation_frame,
182  const ros::Time& time, const ros::Duration& averaging_interval,
183  geometry_msgs::Twist& twist) const;
184 
193  bool waitForTransform(const std::string& target_frame, const std::string& source_frame,
194  const ros::Time& time, const ros::Duration& timeout, const ros::Duration& polling_sleep_duration = ros::Duration(0.01),
195  std::string* error_msg = NULL) const;
202  bool canTransform(const std::string& target_frame, const std::string& source_frame,
203  const ros::Time& time,
204  std::string* error_msg = NULL) const;
205 
214  bool canTransform(const std::string& target_frame, const ros::Time& target_time,
215  const std::string& source_frame, const ros::Time& source_time,
216  const std::string& fixed_frame,
217  std::string* error_msg = NULL) const;
218 
229  bool waitForTransform(const std::string& target_frame, const ros::Time& target_time,
230  const std::string& source_frame, const ros::Time& source_time,
231  const std::string& fixed_frame,
232  const ros::Duration& timeout, const ros::Duration& polling_sleep_duration = ros::Duration(0.01),
233  std::string* error_msg = NULL) const;
234 
237  int getLatestCommonTime(const std::string &source_frame, const std::string &target_frame, ros::Time& time, std::string* error_string) const;
238 
241  void transformQuaternion(const std::string& target_frame, const Stamped<tf::Quaternion>& stamped_in, Stamped<tf::Quaternion>& stamped_out) const;
244  void transformVector(const std::string& target_frame, const Stamped<tf::Vector3>& stamped_in, Stamped<tf::Vector3>& stamped_out) const;
247  void transformPoint(const std::string& target_frame, const Stamped<tf::Point>& stamped_in, Stamped<tf::Point>& stamped_out) const;
250  void transformPose(const std::string& target_frame, const Stamped<tf::Pose>& stamped_in, Stamped<tf::Pose>& stamped_out) const;
251 
254  void transformQuaternion(const std::string& target_frame, const ros::Time& target_time,
255  const Stamped<tf::Quaternion>& stamped_in,
256  const std::string& fixed_frame,
257  Stamped<tf::Quaternion>& stamped_out) const;
260  void transformVector(const std::string& target_frame, const ros::Time& target_time,
261  const Stamped<tf::Vector3>& stamped_in,
262  const std::string& fixed_frame,
263  Stamped<tf::Vector3>& stamped_out) const;
266  void transformPoint(const std::string& target_frame, const ros::Time& target_time,
267  const Stamped<tf::Point>& stamped_in,
268  const std::string& fixed_frame,
269  Stamped<tf::Point>& stamped_out) const;
272  void transformPose(const std::string& target_frame, const ros::Time& target_time,
273  const Stamped<tf::Pose>& stamped_in,
274  const std::string& fixed_frame,
275  Stamped<tf::Pose>& stamped_out) const;
276 
281  //std::string chainAsString(const std::string & target_frame, ros::Time target_time, const std::string & source_frame, ros::Time source_time, const std::string & fixed_frame) const;
282 
287  void chainAsVector(const std::string & target_frame, ros::Time target_time, const std::string & source_frame, ros::Time source_time, const std::string & fixed_frame, std::vector<std::string>& output) const;
288 
292  std::string allFramesAsString() const;
293 
297  std::string allFramesAsDot(double current_time = 0) const;
298 
300  void getFrameStrings(std::vector<std::string>& ids) const;
301 
306  bool getParent(const std::string& frame_id, ros::Time time, std::string& parent) const;
307 
310  bool frameExists(const std::string& frame_id_str) const;
311 
316 
319 
327  boost::signals2::connection addTransformsChangedListener(boost::function<void(void)> callback);
328  void removeTransformsChangedListener(boost::signals2::connection c);
329 
333  std::string getTFPrefix() const { return tf_prefix_;};
334 
335  //Declare that it is safe to call waitForTransform
337  // Get the state of using_dedicated_thread_ from the buffer
339 
340 protected:
341 
342 
343 
355  /******************** Internal Storage ****************/
356 
357 
359  std::string tf_prefix_;
360 
361 
362  public:
363  // A flag to allow falling back to wall time
365 
366  protected:
368  ros::Time now() const {
369  if (!fall_back_to_wall_time_)
370  return ros::Time::now() ;
371  else {
373  return ros::Time(wt.sec, wt.nsec);
374  };
375  }
376 
377  // Allows broadcaster to check ok() before wait for transform
378  // Always returns true in base class
379  virtual bool ok() const;
380 
381  /************************* Internal Functions ****************************/
382 
383 
384 
385 
386 protected:
388 
389 };
390 
391 
393 inline void assertQuaternionValid(const tf::Quaternion & q)
394 {
395  if(std::isnan(q.x()) || std::isnan(q.y()) || std::isnan(q.z()) || std::isnan(q.w()))
396  {
397  std::stringstream ss;
398  ss << "Quaternion contains a NaN" << std::endl;
399  throw tf::InvalidArgument(ss.str());
400  }
401 
402  if(std::fabs(q.x()*q.x() + q.y()*q.y() + q.z()*q.z() + q.w()*q.w() - 1) > 0.01)
403  {
404  std::stringstream ss;
405  ss << "Quaternion malformed, magnitude: " << q.x()*q.x() + q.y()*q.y() + q.z()*q.z() + q.w()*q.w() << " should be 1.0" <<std::endl;
406  throw tf::InvalidArgument(ss.str());
407  } // ROS_ASSERT(std::fabs(q.x()*q.x() + q.y()*q.y() + q.z*q.z() + q.w()*q.w() - 1 < 0.01));
408 };
409 
411 inline void assertQuaternionValid(const geometry_msgs::Quaternion & q)
412 {
413  if(std::isnan(q.x) || std::isnan(q.y) || std::isnan(q.z) || std::isnan(q.w))
414  {
415  std::stringstream ss;
416  ss << "Quaternion contains a NaN" << std::endl;
417  throw tf::InvalidArgument(ss.str());
418  }
419 
420  if(std::fabs(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w - 1) > 0.01)
421  {
422  std::stringstream ss;
423  ss << "Quaternion malformed, magnitude: " << q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w << " should be 1.0" <<std::endl;
424  throw tf::InvalidArgument(ss.str());
425  } // ROS_ASSERT(std::fabs(q.x()*q.x() + q.y()*q.y() + q.z*q.z() + q.w()*q.w() - 1 < 0.01));
426 };
427 }
428 #endif //TF_TF_H
ros::Duration getCacheLength()
Get the duration over which this transformer will cache.
Definition: tf.h:318
bool isUsingDedicatedThread() const
void assertQuaternionValid(const tf::Quaternion &q)
Throw InvalidArgument if quaternion is malformed.
Definition: tf.h:393
void getFrameStrings(std::vector< std::string > &ids) const
A way to get a std::vector of available frame ids.
Definition: tf.cpp:447
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition: Quaternion.h:28
std::string remap(const std::string &frame_id) __attribute__((deprecated))
resolve names
std::string getTFPrefix() const
Get the tf_prefix this is running with.
Definition: tf.h:333
void setUsingDedicatedThread(bool value)
bool getParent(const std::string &frame_id, ros::Time time, std::string &parent) const
Fill the parent of a frame.
Definition: tf.cpp:386
void transformVector(const std::string &target_frame, const Stamped< tf::Vector3 > &stamped_in, Stamped< tf::Vector3 > &stamped_out) const
Transform a Stamped Vector3 into the target frame This can throw anything a lookupTransform can throw...
Definition: tf.cpp:466
void transformQuaternion(const std::string &target_frame, const Stamped< tf::Quaternion > &stamped_in, Stamped< tf::Quaternion > &stamped_out) const
Transform a Stamped Quaternion into the target frame This can throw anything a lookupTransform can th...
Definition: tf.cpp:453
int getLatestCommonTime(const std::string &source_frame, const std::string &target_frame, ros::Time &time, std::string *error_string) const
Return the latest rostime which is common across the spanning set zero if fails to cross...
Definition: tf.cpp:417
bool setTransform(const StampedTransform &transform, const std::string &authority="default_authority")
Add transform information to the tf data structure.
Definition: tf.cpp:229
std::string allFramesAsString() const
A way to see what frames have been cached Useful for debugging.
Definition: tf.cpp:434
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
Return the distance between the ends of this and another vector This is symantically treating the vec...
static const double DEFAULT_CACHE_TIME
10.0 is the default amount of time to cache data in seconds, set in cpp file.
Definition: tf.h:95
Definition: exceptions.h:38
std::string tf_prefix_
The internal storage class for ReferenceTransform.
Definition: tf.h:338
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
Test if a transform is possible.
Definition: tf.cpp:358
ErrorValues
Definition: tf.h:61
void setUsingDedicatedThread(bool value)
Definition: tf.h:336
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
Block until a transform is possible or it times out.
Definition: tf.cpp:348
std::string resolve(const std::string &prefix, const std::string &frame_name)
resolve tf names
Definition: tf.cpp:159
virtual ~Transformer(void)
Definition: tf.cpp:217
void removeTransformsChangedListener(boost::signals2::connection c)
Definition: tf.cpp:578
The data type which will be cross compatable with geometry_msgs This is the tf datatype equivilant of...
void chainAsVector(const std::string &target_frame, ros::Time target_time, const std::string &source_frame, ros::Time source_time, const std::string &fixed_frame, std::vector< std::string > &output) const
Debugging function that will print the spanning chain of transforms. Possible exceptions tf::LookupEx...
Definition: tf.cpp:427
ros::Duration getCacheLength()
bool isUsingDedicatedThread()
Definition: tf.h:338
bool fall_back_to_wall_time_
Definition: tf.h:364
void transformPose(const std::string &target_frame, const Stamped< tf::Pose > &stamped_in, Stamped< tf::Pose > &stamped_out) const
Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as...
Definition: tf.cpp:494
tf2::InvalidArgumentException InvalidArgument
Definition: exceptions.h:45
static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE
The default amount of time to extrapolate //deprecated since integration with tf2.
Definition: tf.h:96
static const unsigned int MAX_GRAPH_DEPTH
The maximum number of time to recurse before assuming the tree has a loop.
Definition: tf.h:94
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
Get the transform between two frames by frame ID.
Definition: tf.cpp:238
ros::Time now() const
Definition: tf.h:368
An internal representation of transform chains.
Definition: tf.h:66
std::string strip_leading_slash(const std::string &frame_name)
Definition: tf.cpp:195
Transformer(bool interpolating=true, ros::Duration cache_time_=ros::Duration(DEFAULT_CACHE_TIME))
Definition: tf.cpp:209
static WallTime now()
static Time now()
void transformPoint(const std::string &target_frame, const Stamped< tf::Point > &stamped_in, Stamped< tf::Point > &stamped_out) const
Transform a Stamped Point into the target frame This can throw anything a lookupTransform can throw a...
Definition: tf.cpp:484
void clear()
Clear all data.
Definition: tf.cpp:223
std::vector< TransformStorage > inverseTransforms
Definition: tf.h:68
std::vector< TransformStorage > forwardTransforms
Definition: tf.h:69
std::string allFramesAsDot(double current_time=0) const
A way to see what frames have been cached Useful for debugging.
Definition: tf.cpp:439
tf2_ros::Buffer tf2_buffer_
Definition: tf.h:387
void lookupTwist(const std::string &tracking_frame, const std::string &observation_frame, const std::string &reference_frame, const tf::Point &reference_point, const std::string &reference_point_frame, const ros::Time &time, const ros::Duration &averaging_interval, geometry_msgs::Twist &twist) const
Lookup the twist of the tracking_frame with respect to the observation frame in the reference_frame u...
Definition: tf.cpp:270
virtual bool ok() const
Definition: tf.cpp:445
void setExtrapolationLimit(const ros::Duration &distance)
Set the distance which tf is allow to extrapolate.
Definition: tf.cpp:397
bool frameExists(const std::string &frame_id_str) const
Check if a frame exists in the tree.
Definition: tf.cpp:392
boost::signals2::connection addTransformsChangedListener(boost::function< void(void)> callback)
Add a callback that happens when a new transform has arrived.
Definition: tf.cpp:573
The Stamped Transform datatype used by tf.
A Class which provides coordinate transforms between any two frames in a system.
Definition: tf.h:90
Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16-byte...
Definition: Vector3.h:38
tf::tfVector4 __attribute__


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Jun 10 2019 12:25:26