vec_3f.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00037 #ifndef FCL_VEC_3F_H
00038 #define FCL_VEC_3F_H
00039 
00040 #include "fcl/config.h"
00041 #include "fcl/data_types.h"
00042 #include "fcl/math/math_details.h"
00043 
00044 #if FCL_HAVE_SSE
00045 #  include "fcl/simd/math_simd_details.h"
00046 #endif
00047 
00048 #include <cmath>
00049 #include <iostream>
00050 #include <limits>
00051 
00052 
00053 namespace fcl
00054 {
00055 
00057 template <typename T>
00058 class Vec3fX
00059 {
00060 public:
00061   typedef typename T::meta_type U;
00062 
00064   T data;
00065 
00066   Vec3fX() {}
00067   Vec3fX(const Vec3fX& other) : data(other.data) {}
00068 
00070   Vec3fX(U x, U y, U z) : data(x, y, z) {}
00071 
00073   Vec3fX(U x) : data(x) {}
00074 
00076   Vec3fX(const T& data_) : data(data_) {}
00077 
00078   inline U operator [] (size_t i) const { return data[i]; }
00079   inline U& operator [] (size_t i) { return data[i]; }
00080 
00081   inline Vec3fX operator + (const Vec3fX& other) const { return Vec3fX(data + other.data); }
00082   inline Vec3fX operator - (const Vec3fX& other) const { return Vec3fX(data - other.data); }
00083   inline Vec3fX operator * (const Vec3fX& other) const { return Vec3fX(data * other.data); }
00084   inline Vec3fX operator / (const Vec3fX& other) const { return Vec3fX(data / other.data); }
00085   inline Vec3fX& operator += (const Vec3fX& other) { data += other.data; return *this; }
00086   inline Vec3fX& operator -= (const Vec3fX& other) { data -= other.data; return *this; }
00087   inline Vec3fX& operator *= (const Vec3fX& other) { data *= other.data; return *this; }
00088   inline Vec3fX& operator /= (const Vec3fX& other) { data /= other.data; return *this; }
00089   inline Vec3fX operator + (U t) const { return Vec3fX(data + t); }
00090   inline Vec3fX operator - (U t) const { return Vec3fX(data - t); }
00091   inline Vec3fX operator * (U t) const { return Vec3fX(data * t); }
00092   inline Vec3fX operator / (U t) const { return Vec3fX(data / t); }
00093   inline Vec3fX& operator += (U t) { data += t; return *this; }
00094   inline Vec3fX& operator -= (U t) { data -= t; return *this; }
00095   inline Vec3fX& operator *= (U t) { data *= t; return *this; }
00096   inline Vec3fX& operator /= (U t) { data /= t; return *this; }
00097   inline Vec3fX operator - () const { return Vec3fX(-data); }
00098   inline Vec3fX cross(const Vec3fX& other) const { return Vec3fX(details::cross_prod(data, other.data)); }
00099   inline U dot(const Vec3fX& other) const { return details::dot_prod3(data, other.data); }
00100   inline Vec3fX& normalize()
00101   {
00102     U sqr_length = details::dot_prod3(data, data);
00103     if(sqr_length > 0)
00104       *this /= (U)sqrt(sqr_length);
00105     return *this;
00106   }
00107 
00108   inline Vec3fX& normalize(bool* signal)
00109   {
00110     U sqr_length = details::dot_prod3(data, data);
00111     if(sqr_length > 0)
00112     {
00113       *this /= (U)sqrt(sqr_length);
00114       *signal = true;
00115     }
00116     else
00117       *signal = false;
00118     return *this;
00119   }
00120 
00121   inline Vec3fX& abs() 
00122   {
00123     data = abs(data);
00124     return *this;
00125   }
00126 
00127   inline U length() const { return sqrt(details::dot_prod3(data, data)); }
00128   inline U sqrLength() const { return details::dot_prod3(data, data); }
00129   inline void setValue(U x, U y, U z) { data.setValue(x, y, z); }
00130   inline void setValue(U x) { data.setValue(x); }
00131   inline bool equal(const Vec3fX& other, U epsilon = std::numeric_limits<U>::epsilon() * 100) const { return details::equal(data, other.data, epsilon); }
00132   inline Vec3fX<T>& negate() { data.negate(); return *this; }
00133 
00134   inline Vec3fX<T>& ubound(const Vec3fX<T>& u)
00135   {
00136     data.ubound(u.data);
00137     return *this;
00138   }
00139 
00140   inline Vec3fX<T>& lbound(const Vec3fX<T>& l)
00141   {
00142     data.lbound(l.data);
00143     return *this;
00144   }
00145 
00146   bool isZero() const
00147   {
00148     return (data[0] == 0) && (data[1] == 0) && (data[2] == 0);
00149   }
00150 
00151 };
00152 
00153 template<typename T>
00154 static inline Vec3fX<T> normalize(const Vec3fX<T>& v)
00155 {
00156   typename T::meta_type sqr_length = details::dot_prod3(v.data, v.data);
00157   if(sqr_length > 0)
00158     return v / (typename T::meta_type)sqrt(sqr_length);
00159   else
00160     return v;
00161 }
00162 
00163 template <typename T>
00164 static inline typename T::meta_type triple(const Vec3fX<T>& x, const Vec3fX<T>& y, const Vec3fX<T>& z)
00165 {
00166   return x.dot(y.cross(z));
00167 }
00168 
00169 template <typename T>
00170 std::ostream& operator << (std::ostream& out, const Vec3fX<T>& x)
00171 {
00172   out << x[0] << " " << x[1] << " " << x[2];
00173   return out;
00174 }
00175 
00176 template <typename T>
00177 static inline Vec3fX<T> min(const Vec3fX<T>& x, const Vec3fX<T>& y)
00178 {
00179   return Vec3fX<T>(details::min(x.data, y.data));
00180 }
00181 
00182 template <typename T>
00183 static inline Vec3fX<T> max(const Vec3fX<T>& x, const Vec3fX<T>& y)
00184 {
00185   return Vec3fX<T>(details::max(x.data, y.data));
00186 }
00187 
00188 template <typename T>
00189 static inline Vec3fX<T> abs(const Vec3fX<T>& x)
00190 {
00191   return Vec3fX<T>(details::abs(x.data));
00192 }
00193 
00194 template <typename T>
00195 void generateCoordinateSystem(const Vec3fX<T>& w, Vec3fX<T>& u, Vec3fX<T>& v)
00196 {
00197   typedef typename T::meta_type U;
00198   U inv_length;
00199   if(std::abs(w[0]) >= std::abs(w[1]))
00200   {
00201     inv_length = (U)1.0 / sqrt(w[0] * w[0] + w[2] * w[2]);
00202     u[0] = -w[2] * inv_length;
00203     u[1] = (U)0;
00204     u[2] = w[0] * inv_length;
00205     v[0] = w[1] * u[2];
00206     v[1] = w[2] * u[0] - w[0] * u[2];
00207     v[2] = -w[1] * u[0];
00208   }
00209   else
00210   {
00211     inv_length = (U)1.0 / sqrt(w[1] * w[1] + w[2] * w[2]);
00212     u[0] = (U)0;
00213     u[1] = w[2] * inv_length;
00214     u[2] = -w[1] * inv_length;
00215     v[0] = w[1] * u[2] - w[2] * u[1];
00216     v[1] = -w[0] * u[2];
00217     v[2] = w[0] * u[1];
00218   }
00219 }
00220 
00221 #if FCL_HAVE_SSE
00222   typedef Vec3fX<details::sse_meta_f4> Vec3f;
00223 #else
00224   typedef Vec3fX<details::Vec3Data<FCL_REAL> > Vec3f;
00225 #endif
00226 
00227 static inline std::ostream& operator << (std::ostream& o, const Vec3f& v)
00228 {
00229   o << "(" << v[0] << " " << v[1] << " " << v[2] << ")";
00230   return o;
00231 }
00232 
00233 
00234 }
00235 
00236 
00237 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


fcl
Author(s): Jia Pan
autogenerated on Tue Jan 15 2013 16:05:31