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 #include <memory>
42 
43 #include <tf/exceptions.h>
44 #include "tf/time_cache.h"
45 #include <boost/unordered_map.hpp>
46 #include <boost/signals2.hpp>
47 #include "geometry_msgs/TwistStamped.h"
48 
49 #include <tf2_ros/buffer.h>
50 #include <ros/macros.h>
51 
52 // Import/export for windows dll's and visibility for gcc shared libraries.
53 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
54  #ifdef tf_EXPORTS // we are building a shared lib/dll
55  #define TF_DECL ROS_HELPER_EXPORT
56  #else // we are using shared lib/dll
57  #define TF_DECL ROS_HELPER_IMPORT
58  #endif
59 #else // ros is being built around static libraries
60  #define TF_DECL
61 #endif
62 
63 namespace tf
64 {
66 std::string resolve(const std::string& prefix, const std::string& frame_name);
67 
69 std::string strip_leading_slash(const std::string& frame_name);
70 
72 ROS_DEPRECATED static inline std::string remap(const std::string& prefix, const std::string& frame_name) { return tf::resolve(prefix, frame_name);}
73 
75 
79 typedef struct
80 {
81  std::vector<TransformStorage > inverseTransforms;
82  std::vector<TransformStorage > forwardTransforms;
84 
104 {
105 public:
106  /************* Constants ***********************/
107  static const unsigned int MAX_GRAPH_DEPTH = 100UL;
108  static const double DEFAULT_CACHE_TIME;
109  static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0ULL;
110 
111 
117  Transformer(bool interpolating = true,
118  ros::Duration cache_time_ = ros::Duration(DEFAULT_CACHE_TIME));
119  virtual ~Transformer(void);
120 
122  void clear();
123 
129  bool setTransform(const StampedTransform& transform, const std::string & authority = "default_authority");
130 
131  /*********** Accessors *************/
132 
142  void lookupTransform(const std::string& target_frame, const std::string& source_frame,
143  const ros::Time& time, StampedTransform& transform) const;
155  void lookupTransform(const std::string& target_frame, const ros::Time& target_time,
156  const std::string& source_frame, const ros::Time& source_time,
157  const std::string& fixed_frame, StampedTransform& transform) const;
158 
179  void lookupTwist(const std::string& tracking_frame, const std::string& observation_frame, const std::string& reference_frame,
180  const tf::Point & reference_point, const std::string& reference_point_frame,
181  const ros::Time& time, const ros::Duration& averaging_interval,
182  geometry_msgs::Twist& twist) const;
183 
194  void lookupTwist(const std::string& tracking_frame, const std::string& observation_frame,
195  const ros::Time& time, const ros::Duration& averaging_interval,
196  geometry_msgs::Twist& twist) const;
197 
206  bool waitForTransform(const std::string& target_frame, const std::string& source_frame,
207  const ros::Time& time, const ros::Duration& timeout, const ros::Duration& polling_sleep_duration = ros::Duration(0.01),
208  std::string* error_msg = NULL) const;
215  bool canTransform(const std::string& target_frame, const std::string& source_frame,
216  const ros::Time& time,
217  std::string* error_msg = NULL) const;
218 
227  bool canTransform(const std::string& target_frame, const ros::Time& target_time,
228  const std::string& source_frame, const ros::Time& source_time,
229  const std::string& fixed_frame,
230  std::string* error_msg = NULL) const;
231 
242  bool waitForTransform(const std::string& target_frame, const ros::Time& target_time,
243  const std::string& source_frame, const ros::Time& source_time,
244  const std::string& fixed_frame,
245  const ros::Duration& timeout, const ros::Duration& polling_sleep_duration = ros::Duration(0.01),
246  std::string* error_msg = NULL) const;
247 
250  int getLatestCommonTime(const std::string &source_frame, const std::string &target_frame, ros::Time& time, std::string* error_string) const;
251 
254  void transformQuaternion(const std::string& target_frame, const Stamped<tf::Quaternion>& stamped_in, Stamped<tf::Quaternion>& stamped_out) const;
257  void transformVector(const std::string& target_frame, const Stamped<tf::Vector3>& stamped_in, Stamped<tf::Vector3>& stamped_out) const;
260  void transformPoint(const std::string& target_frame, const Stamped<tf::Point>& stamped_in, Stamped<tf::Point>& stamped_out) const;
263  void transformPose(const std::string& target_frame, const Stamped<tf::Pose>& stamped_in, Stamped<tf::Pose>& stamped_out) const;
264 
267  void transformQuaternion(const std::string& target_frame, const ros::Time& target_time,
268  const Stamped<tf::Quaternion>& stamped_in,
269  const std::string& fixed_frame,
270  Stamped<tf::Quaternion>& stamped_out) const;
273  void transformVector(const std::string& target_frame, const ros::Time& target_time,
274  const Stamped<tf::Vector3>& stamped_in,
275  const std::string& fixed_frame,
276  Stamped<tf::Vector3>& stamped_out) const;
279  void transformPoint(const std::string& target_frame, const ros::Time& target_time,
280  const Stamped<tf::Point>& stamped_in,
281  const std::string& fixed_frame,
282  Stamped<tf::Point>& stamped_out) const;
285  void transformPose(const std::string& target_frame, const ros::Time& target_time,
286  const Stamped<tf::Pose>& stamped_in,
287  const std::string& fixed_frame,
288  Stamped<tf::Pose>& stamped_out) const;
289 
294  //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;
295 
300  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;
301 
305  std::string allFramesAsString() const;
306 
310  std::string allFramesAsDot(double current_time = 0) const;
311 
313  void getFrameStrings(std::vector<std::string>& ids) const;
314 
319  bool getParent(const std::string& frame_id, ros::Time time, std::string& parent) const;
320 
323  bool frameExists(const std::string& frame_id_str) const;
324 
328  void setExtrapolationLimit(const ros::Duration& distance);
329 
331  ros::Duration getCacheLength() { return tf2_buffer_ptr_->getCacheLength();}
332 
340  boost::signals2::connection addTransformsChangedListener(boost::function<void(void)> callback);
341  void removeTransformsChangedListener(boost::signals2::connection c);
342 
346  std::string getTFPrefix() const { return tf_prefix_;}
347 
348  //Declare that it is safe to call waitForTransform
349  void setUsingDedicatedThread(bool value) { tf2_buffer_ptr_->setUsingDedicatedThread(value);}
350  // Get the state of using_dedicated_thread_ from the buffer
351  bool isUsingDedicatedThread() { return tf2_buffer_ptr_->isUsingDedicatedThread();}
352 
353  // Get a copy of the shared_ptr containing the tf2_ros::Buffer object
354  std::shared_ptr<tf2_ros::Buffer> getTF2BufferPtr() { return tf2_buffer_ptr_;}
355 
356 protected:
357 
358 
359 
371  /******************** Internal Storage ****************/
372 
373 
375  std::string tf_prefix_;
376 
377 
378  public:
379  // A flag to allow falling back to wall time
381 
382  protected:
384  ros::Time now() const {
385  if (!fall_back_to_wall_time_)
386  return ros::Time::now() ;
387  else {
389  return ros::Time(wt.sec, wt.nsec);
390  };
391  }
392 
393  // Allows broadcaster to check ok() before wait for transform
394  // Always returns true in base class
395  virtual bool ok() const;
396 
397  /************************* Internal Functions ****************************/
398 
399 
400 
401 
402 protected:
403  std::shared_ptr<tf2_ros::Buffer> tf2_buffer_ptr_;
404 
405 };
406 
407 
409 inline void assertQuaternionValid(const tf::Quaternion & q)
410 {
411  if(std::isnan(q.x()) || std::isnan(q.y()) || std::isnan(q.z()) || std::isnan(q.w()))
412  {
413  std::stringstream ss;
414  ss << "Quaternion contains a NaN" << std::endl;
415  throw tf::InvalidArgument(ss.str());
416  }
417 
418  if(std::fabs(q.x()*q.x() + q.y()*q.y() + q.z()*q.z() + q.w()*q.w() - 1) > 0.01)
419  {
420  std::stringstream ss;
421  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;
422  throw tf::InvalidArgument(ss.str());
423  } // ROS_ASSERT(std::fabs(q.x()*q.x() + q.y()*q.y() + q.z*q.z() + q.w()*q.w() - 1 < 0.01));
424 }
425 
427 inline void assertQuaternionValid(const geometry_msgs::Quaternion & q)
428 {
429  if(std::isnan(q.x) || std::isnan(q.y) || std::isnan(q.z) || std::isnan(q.w))
430  {
431  std::stringstream ss;
432  ss << "Quaternion contains a NaN" << std::endl;
433  throw tf::InvalidArgument(ss.str());
434  }
435 
436  if(std::fabs(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w - 1) > 0.01)
437  {
438  std::stringstream ss;
439  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;
440  throw tf::InvalidArgument(ss.str());
441  } // ROS_ASSERT(std::fabs(q.x()*q.x() + q.y()*q.y() + q.z*q.z() + q.w()*q.w() - 1 < 0.01));
442 }
443 }
444 #endif //TF_TF_H
tf::EXTRAPOLATION_ERROR
@ EXTRAPOLATION_ERROR
Definition: tf.h:74
tf::Transformer::getCacheLength
ros::Duration getCacheLength()
Get the duration over which this transformer will cache.
Definition: tf.h:331
exceptions.h
tf::CONNECTIVITY_ERROR
@ CONNECTIVITY_ERROR
Definition: tf.h:74
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
resolve tf names
Definition: tf.cpp:159
buffer.h
tf::assertQuaternionValid
void assertQuaternionValid(const tf::Quaternion &q)
Throw InvalidArgument if quaternion is malformed.
Definition: tf.h:409
tf::Transformer
A Class which provides coordinate transforms between any two frames in a system.
Definition: tf.h:103
tf::StampedTransform
The Stamped Transform datatype used by tf.
Definition: transform_datatypes.h:81
ROS_DEPRECATED
#define ROS_DEPRECATED
tf::Transformer::isUsingDedicatedThread
bool isUsingDedicatedThread()
Definition: tf.h:351
ok
ROSCPP_DECL bool ok()
tf::Transformer::tf_prefix_
std::string tf_prefix_
The internal storage class for ReferenceTransform.
Definition: tf.h:375
tf::Stamped
The data type which will be cross compatable with geometry_msgs This is the tf datatype equivilant of...
Definition: transform_datatypes.h:57
tf::TransformLists::inverseTransforms
std::vector< TransformStorage > inverseTransforms
Definition: tf.h:81
tf::Point
tf::Vector3 Point
Definition: transform_datatypes.h:49
tf::Transformer::setUsingDedicatedThread
void setUsingDedicatedThread(bool value)
Definition: tf.h:349
tf::Transformer::DEFAULT_CACHE_TIME
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:108
tf::InvalidArgument
tf2::InvalidArgumentException InvalidArgument
Definition: exceptions.h:45
ros::WallTime::now
static WallTime now()
tf::Transformer::getTFPrefix
std::string getTFPrefix() const
Get the tf_prefix this is running with.
Definition: tf.h:346
tf::TransformLists::forwardTransforms
std::vector< TransformStorage > forwardTransforms
Definition: tf.h:82
time_cache.h
tf::ErrorValues
ErrorValues
Definition: tf.h:74
ros::WallTime
TimeBase< WallTime, WallDuration >::sec
uint32_t sec
TimeBase< WallTime, WallDuration >::nsec
uint32_t nsec
tf::Transformer::fall_back_to_wall_time_
bool fall_back_to_wall_time_
Definition: tf.h:380
tf::Transformer::getTF2BufferPtr
std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr()
Definition: tf.h:354
tf::TransformLists
An internal representation of transform chains.
Definition: tf.h:79
ros::Time
tf::NO_ERROR
@ NO_ERROR
Definition: tf.h:74
tf::strip_leading_slash
std::string strip_leading_slash(const std::string &frame_name)
Definition: tf.cpp:195
tf::Transformer::tf2_buffer_ptr_
std::shared_ptr< tf2_ros::Buffer > tf2_buffer_ptr_
Definition: tf.h:403
TF_DECL
#define TF_DECL
Definition: tf.h:60
tf::Transformer::now
ros::Time now() const
Definition: tf.h:384
tf
Definition: exceptions.h:38
tf::LOOKUP_ERROR
@ LOOKUP_ERROR
Definition: tf.h:74
macros.h
ros::Duration
tf::remap
static ROS_DEPRECATED std::string remap(const std::string &prefix, const std::string &frame_name)
Definition: tf.h:72
tf::Quaternion
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition: Quaternion.h:30
ros::Time::now
static Time now()


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sat Aug 19 2023 02:38:08