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 // Boost winapi.h includes winerror.h. Subsequently NO_ERROR gets defined
53 // and which conflicts with tf::NO_ERROR.
54 #if defined(_WIN32) && defined(NO_ERROR)
55  #undef NO_ERROR
56 #endif
57 
58 // Import/export for windows dll's and visibility for gcc shared libraries.
59 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
60  #ifdef tf_EXPORTS // we are building a shared lib/dll
61  #define TF_DECL ROS_HELPER_EXPORT
62  #else // we are using shared lib/dll
63  #define TF_DECL ROS_HELPER_IMPORT
64  #endif
65 #else // ros is being built around static libraries
66  #define TF_DECL
67 #endif
68 
69 namespace tf
70 {
72 std::string resolve(const std::string& prefix, const std::string& frame_name);
73 
75 std::string strip_leading_slash(const std::string& frame_name);
76 
78 ROS_DEPRECATED static inline std::string remap(const std::string& prefix, const std::string& frame_name) { return tf::resolve(prefix, frame_name);}
79 
81 
85 typedef struct
86 {
87  std::vector<TransformStorage > inverseTransforms;
88  std::vector<TransformStorage > forwardTransforms;
90 
110 {
111 public:
112  /************* Constants ***********************/
113  static const unsigned int MAX_GRAPH_DEPTH = 100UL;
114  static const double DEFAULT_CACHE_TIME;
115  static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0ULL;
116 
117 
123  Transformer(bool interpolating = true,
124  ros::Duration cache_time_ = ros::Duration(DEFAULT_CACHE_TIME));
125  virtual ~Transformer(void);
126 
128  void clear();
129 
135  bool setTransform(const StampedTransform& transform, const std::string & authority = "default_authority");
136 
137  /*********** Accessors *************/
138 
148  void lookupTransform(const std::string& target_frame, const std::string& source_frame,
149  const ros::Time& time, StampedTransform& transform) const;
161  void lookupTransform(const std::string& target_frame, const ros::Time& target_time,
162  const std::string& source_frame, const ros::Time& source_time,
163  const std::string& fixed_frame, StampedTransform& transform) const;
164 
185  void lookupTwist(const std::string& tracking_frame, const std::string& observation_frame, const std::string& reference_frame,
186  const tf::Point & reference_point, const std::string& reference_point_frame,
187  const ros::Time& time, const ros::Duration& averaging_interval,
188  geometry_msgs::Twist& twist) const;
189 
200  void lookupTwist(const std::string& tracking_frame, const std::string& observation_frame,
201  const ros::Time& time, const ros::Duration& averaging_interval,
202  geometry_msgs::Twist& twist) const;
203 
212  bool waitForTransform(const std::string& target_frame, const std::string& source_frame,
213  const ros::Time& time, const ros::Duration& timeout, const ros::Duration& polling_sleep_duration = ros::Duration(0.01),
214  std::string* error_msg = NULL) const;
221  bool canTransform(const std::string& target_frame, const std::string& source_frame,
222  const ros::Time& time,
223  std::string* error_msg = NULL) const;
224 
233  bool canTransform(const std::string& target_frame, const ros::Time& target_time,
234  const std::string& source_frame, const ros::Time& source_time,
235  const std::string& fixed_frame,
236  std::string* error_msg = NULL) const;
237 
248  bool waitForTransform(const std::string& target_frame, const ros::Time& target_time,
249  const std::string& source_frame, const ros::Time& source_time,
250  const std::string& fixed_frame,
251  const ros::Duration& timeout, const ros::Duration& polling_sleep_duration = ros::Duration(0.01),
252  std::string* error_msg = NULL) const;
253 
256  int getLatestCommonTime(const std::string &source_frame, const std::string &target_frame, ros::Time& time, std::string* error_string) const;
257 
260  void transformQuaternion(const std::string& target_frame, const Stamped<tf::Quaternion>& stamped_in, Stamped<tf::Quaternion>& stamped_out) const;
263  void transformVector(const std::string& target_frame, const Stamped<tf::Vector3>& stamped_in, Stamped<tf::Vector3>& stamped_out) const;
266  void transformPoint(const std::string& target_frame, const Stamped<tf::Point>& stamped_in, Stamped<tf::Point>& stamped_out) const;
269  void transformPose(const std::string& target_frame, const Stamped<tf::Pose>& stamped_in, Stamped<tf::Pose>& stamped_out) const;
270 
273  void transformQuaternion(const std::string& target_frame, const ros::Time& target_time,
274  const Stamped<tf::Quaternion>& stamped_in,
275  const std::string& fixed_frame,
276  Stamped<tf::Quaternion>& stamped_out) const;
279  void transformVector(const std::string& target_frame, const ros::Time& target_time,
280  const Stamped<tf::Vector3>& stamped_in,
281  const std::string& fixed_frame,
282  Stamped<tf::Vector3>& stamped_out) const;
285  void transformPoint(const std::string& target_frame, const ros::Time& target_time,
286  const Stamped<tf::Point>& stamped_in,
287  const std::string& fixed_frame,
288  Stamped<tf::Point>& stamped_out) const;
291  void transformPose(const std::string& target_frame, const ros::Time& target_time,
292  const Stamped<tf::Pose>& stamped_in,
293  const std::string& fixed_frame,
294  Stamped<tf::Pose>& stamped_out) const;
295 
300  //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;
301 
306  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;
307 
311  std::string allFramesAsString() const;
312 
316  std::string allFramesAsDot(double current_time = 0) const;
317 
319  void getFrameStrings(std::vector<std::string>& ids) const;
320 
325  bool getParent(const std::string& frame_id, ros::Time time, std::string& parent) const;
326 
329  bool frameExists(const std::string& frame_id_str) const;
330 
334  void setExtrapolationLimit(const ros::Duration& distance);
335 
337  ros::Duration getCacheLength() { return tf2_buffer_ptr_->getCacheLength();}
338 
346  boost::signals2::connection addTransformsChangedListener(boost::function<void(void)> callback);
347  void removeTransformsChangedListener(boost::signals2::connection c);
348 
352  std::string getTFPrefix() const { return tf_prefix_;};
353 
354  //Declare that it is safe to call waitForTransform
355  void setUsingDedicatedThread(bool value) { tf2_buffer_ptr_->setUsingDedicatedThread(value);};
356  // Get the state of using_dedicated_thread_ from the buffer
357  bool isUsingDedicatedThread() { return tf2_buffer_ptr_->isUsingDedicatedThread();};
358 
359  // Get a copy of the shared_ptr containing the tf2_ros::Buffer object
360  std::shared_ptr<tf2_ros::Buffer> getTF2BufferPtr() { return tf2_buffer_ptr_;};
361 
362 protected:
363 
364 
365 
377  /******************** Internal Storage ****************/
378 
379 
381  std::string tf_prefix_;
382 
383 
384  public:
385  // A flag to allow falling back to wall time
387 
388  protected:
390  ros::Time now() const {
391  if (!fall_back_to_wall_time_)
392  return ros::Time::now() ;
393  else {
395  return ros::Time(wt.sec, wt.nsec);
396  };
397  }
398 
399  // Allows broadcaster to check ok() before wait for transform
400  // Always returns true in base class
401  virtual bool ok() const;
402 
403  /************************* Internal Functions ****************************/
404 
405 
406 
407 
408 protected:
409  std::shared_ptr<tf2_ros::Buffer> tf2_buffer_ptr_;
410 
411 };
412 
413 
415 inline void assertQuaternionValid(const tf::Quaternion & q)
416 {
417  if(std::isnan(q.x()) || std::isnan(q.y()) || std::isnan(q.z()) || std::isnan(q.w()))
418  {
419  std::stringstream ss;
420  ss << "Quaternion contains a NaN" << std::endl;
421  throw tf::InvalidArgument(ss.str());
422  }
423 
424  if(std::fabs(q.x()*q.x() + q.y()*q.y() + q.z()*q.z() + q.w()*q.w() - 1) > 0.01)
425  {
426  std::stringstream ss;
427  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;
428  throw tf::InvalidArgument(ss.str());
429  } // ROS_ASSERT(std::fabs(q.x()*q.x() + q.y()*q.y() + q.z*q.z() + q.w()*q.w() - 1 < 0.01));
430 }
431 
433 inline void assertQuaternionValid(const geometry_msgs::Quaternion & q)
434 {
435  if(std::isnan(q.x) || std::isnan(q.y) || std::isnan(q.z) || std::isnan(q.w))
436  {
437  std::stringstream ss;
438  ss << "Quaternion contains a NaN" << std::endl;
439  throw tf::InvalidArgument(ss.str());
440  }
441 
442  if(std::fabs(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w - 1) > 0.01)
443  {
444  std::stringstream ss;
445  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;
446  throw tf::InvalidArgument(ss.str());
447  } // ROS_ASSERT(std::fabs(q.x()*q.x() + q.y()*q.y() + q.z*q.z() + q.w()*q.w() - 1 < 0.01));
448 }
449 }
450 #endif //TF_TF_H
ros::Duration getCacheLength()
Get the duration over which this transformer will cache.
Definition: tf.h:337
void assertQuaternionValid(const tf::Quaternion &q)
Throw InvalidArgument if quaternion is malformed.
Definition: tf.h:415
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition: Quaternion.h:30
static ROS_DEPRECATED std::string remap(const std::string &prefix, const std::string &frame_name)
Definition: tf.h:78
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:114
Definition: exceptions.h:38
tf::Vector3 Point
std::string tf_prefix_
The internal storage class for ReferenceTransform.
Definition: tf.h:360
ErrorValues
Definition: tf.h:80
void setUsingDedicatedThread(bool value)
Definition: tf.h:355
std::string resolve(const std::string &prefix, const std::string &frame_name)
resolve tf names
Definition: tf.cpp:158
std::string getTFPrefix() const
Get the tf_prefix this is running with.
Definition: tf.h:352
The data type which will be cross compatable with geometry_msgs This is the tf datatype equivilant of...
bool isUsingDedicatedThread()
Definition: tf.h:357
bool fall_back_to_wall_time_
Definition: tf.h:386
ROSCPP_DECL bool ok()
tf2::InvalidArgumentException InvalidArgument
Definition: exceptions.h:45
std::shared_ptr< tf2_ros::Buffer > tf2_buffer_ptr_
Definition: tf.h:409
#define ROS_DEPRECATED
An internal representation of transform chains.
Definition: tf.h:85
std::string strip_leading_slash(const std::string &frame_name)
Definition: tf.cpp:194
static WallTime now()
#define TF_DECL
Definition: tf.h:66
ros::Time now() const
Definition: tf.h:390
static Time now()
std::vector< TransformStorage > inverseTransforms
Definition: tf.h:87
std::vector< TransformStorage > forwardTransforms
Definition: tf.h:88
The Stamped Transform datatype used by tf.
A Class which provides coordinate transforms between any two frames in a system.
Definition: tf.h:109


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Feb 28 2022 22:26:19