transform.h
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 
00030 #ifndef TRANSFORM_UTIL_TRANSFORM_H_
00031 #define TRANSFORM_UTIL_TRANSFORM_H_
00032 
00033 #include <boost/shared_ptr.hpp>
00034 
00035 #include <ros/ros.h>
00036 
00037 #include <tf/transform_datatypes.h>
00038 
00039 namespace swri_transform_util
00040 {
00049   class TransformImpl
00050   {
00051   public:
00052     TransformImpl() {}
00053     virtual ~TransformImpl() {}
00054 
00061     virtual void Transform(
00062       const tf::Vector3& v_in, tf::Vector3& v_out) const = 0;
00063     
00071     virtual tf::Quaternion GetOrientation() const
00072     {
00073       tf::Vector3 offset;
00074       Transform(tf::Vector3(1, 0, 0), offset);
00075 
00076       tf::Vector3 origin;
00077       Transform(tf::Vector3(0, 0, 0), origin);
00078 
00079       tf::Vector3 vector = offset - origin;
00080 
00081       // Use the "half-way quaternion method" of summing and normalizing a
00082       // quaternion with twice the rotation between the vector and the x-axis and
00083       // the zero rotation.
00084 
00085       tf::Vector3 cross = tf::Vector3(1, 0, 0).cross(vector);
00086       double w = vector.length() + tf::Vector3(1, 0, 0).dot(vector);
00087       return tf::Quaternion(cross.x(), cross.y(), cross.z(), w).normalized();
00088     }
00089 
00090     virtual boost::shared_ptr<TransformImpl> Inverse() const = 0;
00091     
00093     ros::Time stamp_;
00094   };
00095   typedef boost::shared_ptr<TransformImpl> TransformImplPtr;
00096 
00105   class Transform
00106   {
00107   public:
00111     Transform();
00112 
00118     explicit Transform(const tf::Transform& transform);
00119     
00125     explicit Transform(const tf::StampedTransform& transform);
00126 
00132     explicit Transform(boost::shared_ptr<TransformImpl> transform);
00133 
00141     Transform& operator=(const tf::Transform transform);
00142 
00150     Transform& operator=(boost::shared_ptr<TransformImpl> transform);
00151 
00159     tf::Vector3 operator()(const tf::Vector3& v) const;
00160 
00168     tf::Vector3 operator*(const tf::Vector3& v) const;
00169 
00177     tf::Quaternion operator*(const tf::Quaternion& q) const;
00178 
00184     tf::Transform GetTF() const;
00185 
00191     Transform Inverse() const;
00192 
00201     tf::Vector3 GetOrigin() const;
00202 
00208     tf::Quaternion GetOrientation() const;
00209     
00214     ros::Time GetStamp() { return transform_->stamp_; }
00215 
00216   private:
00218     boost::shared_ptr<TransformImpl> transform_;
00219   };
00220 
00225   class IdentityTransform : public TransformImpl
00226   {
00227   public:
00231     IdentityTransform() { stamp_ = ros::Time::now(); }
00232 
00239     virtual void Transform(const tf::Vector3& v_in, tf::Vector3& v_out) const;
00240     virtual TransformImplPtr Inverse() const;
00241   };
00242 
00247   class TfTransform : public TransformImpl
00248   {
00249   public:
00254     explicit TfTransform(const tf::Transform& transform);
00255 
00260     explicit TfTransform(const tf::StampedTransform& transform);
00261 
00268     virtual void Transform(const tf::Vector3& v_in, tf::Vector3& v_out) const;
00269 
00274     virtual tf::Quaternion GetOrientation() const;
00275     virtual TransformImplPtr Inverse() const;
00276 
00277   protected:
00278     tf::Transform transform_;
00279   };
00280 }
00281 
00282 #endif  // TRANSFORM_UTIL_TRANSFORM_H_


swri_transform_util
Author(s): Marc Alban
autogenerated on Tue Oct 3 2017 03:19:48