transform.h
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
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 Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from 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 <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
30 #ifndef TRANSFORM_UTIL_TRANSFORM_H_
31 #define TRANSFORM_UTIL_TRANSFORM_H_
32 
33 #include <boost/shared_ptr.hpp>
34 
35 #include <ros/ros.h>
36 
37 #include <tf/transform_datatypes.h>
38 
39 namespace swri_transform_util
40 {
50  {
51  public:
53  virtual ~TransformImpl() {}
54 
61  virtual void Transform(
62  const tf::Vector3& v_in, tf::Vector3& v_out) const = 0;
63 
72  {
73  tf::Vector3 offset;
74  Transform(tf::Vector3(1, 0, 0), offset);
75 
76  tf::Vector3 origin;
77  Transform(tf::Vector3(0, 0, 0), origin);
78 
79  tf::Vector3 vector = offset - origin;
80 
81  // Use the "half-way quaternion method" of summing and normalizing a
82  // quaternion with twice the rotation between the vector and the x-axis and
83  // the zero rotation.
84 
85  tf::Vector3 cross = tf::Vector3(1, 0, 0).cross(vector);
86  double w = vector.length() + tf::Vector3(1, 0, 0).dot(vector);
87  return tf::Quaternion(cross.x(), cross.y(), cross.z(), w).normalized();
88  }
89 
90  virtual boost::shared_ptr<TransformImpl> Inverse() const = 0;
91 
94  };
96 
105  class Transform
106  {
107  public:
111  Transform();
112 
118  explicit Transform(const tf::Transform& transform);
119 
125  explicit Transform(const tf::StampedTransform& transform);
126 
132  explicit Transform(boost::shared_ptr<TransformImpl> transform);
133 
141  Transform& operator=(const tf::Transform transform);
142 
150  Transform& operator=(boost::shared_ptr<TransformImpl> transform);
151 
159  tf::Vector3 operator()(const tf::Vector3& v) const;
160 
168  tf::Vector3 operator*(const tf::Vector3& v) const;
169 
177  tf::Quaternion operator*(const tf::Quaternion& q) const;
178 
184  tf::Transform GetTF() const;
185 
191  Transform Inverse() const;
192 
201  tf::Vector3 GetOrigin() const;
202 
209 
214  ros::Time GetStamp() { return transform_->stamp_; }
215 
216  private:
219  };
220 
226  {
227  public:
232 
239  virtual void Transform(const tf::Vector3& v_in, tf::Vector3& v_out) const;
240  virtual TransformImplPtr Inverse() const;
241  };
242 
247  class TfTransform : public TransformImpl
248  {
249  public:
254  explicit TfTransform(const tf::Transform& transform);
255 
260  explicit TfTransform(const tf::StampedTransform& transform);
261 
268  virtual void Transform(const tf::Vector3& v_in, tf::Vector3& v_out) const;
269 
274  virtual tf::Quaternion GetOrientation() const;
275  virtual TransformImplPtr Inverse() const;
276 
277  protected:
279  };
280 }
281 
282 #endif // TRANSFORM_UTIL_TRANSFORM_H_
An abstraction of the tf::Transform class to support transforms in addition to the rigid transforms s...
Definition: transform.h:105
TFSIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
virtual tf::Quaternion GetOrientation() const
Get the orientation of this transform.
Definition: transform.h:71
virtual void Transform(const tf::Vector3 &v_in, tf::Vector3 &v_out) const =0
Apply this transform to a 3D vector.
Specialization of swri_transform_util::TransformImpl that represents the identity transform...
Definition: transform.h:225
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const
ros::Time GetStamp()
Get the time stamp of the transform.
Definition: transform.h:214
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE Vector3 normalized() const
TFSIMD_FORCE_INLINE tfScalar dot(const Vector3 &v) const
TFSIMD_FORCE_INLINE const tfScalar & z() const
Base class for Transform implementations.
Definition: transform.h:49
TFSIMD_FORCE_INLINE const tfScalar & y() const
boost::shared_ptr< TransformImpl > transform_
Pointer to the implementation of the transform.
Definition: transform.h:218
TFSIMD_FORCE_INLINE const tfScalar & w() const
ros::Time stamp_
Time stamp for this transform.
Definition: transform.h:93
virtual boost::shared_ptr< TransformImpl > Inverse() const =0
Specialization of swri_transform_util::TransformImpl that performs TF transformation.
Definition: transform.h:247
boost::shared_ptr< TransformImpl > TransformImplPtr
Definition: transform.h:95
IdentityTransform()
Construct an identity transform.
Definition: transform.h:231
TFSIMD_FORCE_INLINE tfScalar length() const


swri_transform_util
Author(s): Marc Alban
autogenerated on Tue Apr 6 2021 02:50:46