octomap 1.5.0
|
00001 // $Id: Vector3.h 269 2011-08-18 16:00:50Z kai_wurm $ 00002 00011 /* 00012 * Copyright (c) 2009-2011, K. M. Wurm, A. Hornung, University of Freiburg 00013 * All rights reserved. 00014 * 00015 * Redistribution and use in source and binary forms, with or without 00016 * modification, are permitted provided that the following conditions are met: 00017 * 00018 * * Redistributions of source code must retain the above copyright 00019 * notice, this list of conditions and the following disclaimer. 00020 * * Redistributions in binary form must reproduce the above copyright 00021 * notice, this list of conditions and the following disclaimer in the 00022 * documentation and/or other materials provided with the distribution. 00023 * * Neither the name of the University of Freiburg nor the names of its 00024 * contributors may be used to endorse or promote products derived from 00025 * this software without specific prior written permission. 00026 * 00027 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00028 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00029 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00030 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00031 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00032 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00033 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00034 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00035 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00036 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00037 * POSSIBILITY OF SUCH DAMAGE. 00038 */ 00039 00040 #ifndef OCTOMATH_VECTOR3_H 00041 #define OCTOMATH_VECTOR3_H 00042 00043 #include <iostream> 00044 #include <math.h> 00045 00046 #include <octomap/octomap_deprecated.h> 00047 00048 00049 namespace octomath { 00050 00058 class Vector3 { 00059 public: 00060 00064 Vector3 () { data[0] = data[1] = data[2] = 0; } 00065 00071 Vector3 (const Vector3& other) { 00072 data[0] = other(0); 00073 data[1] = other(1); 00074 data[2] = other(2); 00075 } 00076 00083 Vector3 (float x, float y, float z) { 00084 data[0] = x; 00085 data[1] = y; 00086 data[2] = z; 00087 } 00088 00089 00090 /* inline Eigen3::Vector3f getVector3f() const { return Eigen3::Vector3f(data[0], data[1], data[2]) ; } */ 00091 /* inline Eigen3::Vector4f& getVector4f() { return data; } */ 00092 /* inline Eigen3::Vector4f getVector4f() const { return data; } */ 00093 00099 inline Vector3& operator= (const Vector3& other) { 00100 data[0] = other(0); 00101 data[1] = other(1); 00102 data[2] = other(2); 00103 return *this; 00104 } 00105 00106 00115 inline Vector3 cross (const Vector3& other) const 00116 { 00117 //return (data.start<3> ().cross (other.data.start<3> ())); 00118 // \note should this be renamed? 00119 return Vector3(y()*other.z() - z()*other.y(), 00120 z()*other.x() - x()*other.z(), 00121 x()*other.y() - y()*other.x()); 00122 } 00123 00124 inline double dot (const Vector3& other) const 00125 { 00126 return x()*other.x() + y()*other.y() + z()*other.z(); 00127 } 00128 00129 inline const float& operator() (unsigned int i) const 00130 { 00131 return data[i]; 00132 } 00133 inline float& operator() (unsigned int i) 00134 { 00135 return data[i]; 00136 } 00137 00138 inline float& x() 00139 { 00140 return operator()(0); 00141 } 00142 00143 inline float& y() 00144 { 00145 return operator()(1); 00146 } 00147 00148 inline float& z() 00149 { 00150 return operator()(2); 00151 } 00152 00153 inline const float& x() const 00154 { 00155 return operator()(0); 00156 } 00157 00158 inline const float& y() const 00159 { 00160 return operator()(1); 00161 } 00162 00163 inline const float& z() const 00164 { 00165 return operator()(2); 00166 } 00167 00168 inline float& roll() 00169 { 00170 return operator()(0); 00171 } 00172 00173 inline float& pitch() 00174 { 00175 return operator()(1); 00176 } 00177 00178 inline float& yaw() 00179 { 00180 return operator()(2); 00181 } 00182 00183 inline const float& roll() const 00184 { 00185 return operator()(0); 00186 } 00187 00188 inline const float& pitch() const 00189 { 00190 return operator()(1); 00191 } 00192 00193 inline const float& yaw() const 00194 { 00195 return operator()(2); 00196 } 00197 00198 inline Vector3 operator- () const 00199 { 00200 Vector3 result; 00201 result(0) = -data[0]; 00202 result(1) = -data[1]; 00203 result(2) = -data[2]; 00204 return result; 00205 } 00206 00207 inline Vector3 operator+ (const Vector3 &other) const 00208 { 00209 Vector3 result(*this); 00210 result(0) += other(0); 00211 result(1) += other(1); 00212 result(2) += other(2); 00213 return result; 00214 } 00215 00216 inline Vector3 operator* (float x) const { 00217 Vector3 result(*this); 00218 result(0) *= x; 00219 result(1) *= x; 00220 result(2) *= x; 00221 return result; 00222 } 00223 00224 inline Vector3 operator- (const Vector3 &other) const 00225 { 00226 Vector3 result(*this); 00227 result(0) -= other(0); 00228 result(1) -= other(1); 00229 result(2) -= other(2); 00230 return result; 00231 } 00232 00233 inline void operator+= (const Vector3 &other) 00234 { 00235 data[0] += other(0); 00236 data[1] += other(1); 00237 data[2] += other(2); 00238 } 00239 00240 inline void operator-= (const Vector3& other) { 00241 data[0] -= other(0); 00242 data[1] -= other(1); 00243 data[2] -= other(2); 00244 } 00245 00246 inline void operator/= (float x) { 00247 data[0] /= x; 00248 data[1] /= x; 00249 data[2] /= x; 00250 } 00251 00252 inline void operator*= (float x) { 00253 data[0] *= x; 00254 data[1] *= x; 00255 data[2] *= x; 00256 } 00257 00258 inline bool operator== (const Vector3 &other) const { 00259 for (unsigned int i=0; i<3; i++) { 00260 if (operator()(i) != other(i)) 00261 return false; 00262 } 00263 return true; 00264 } 00265 00266 inline double norm () const { 00267 double n = 0; 00268 for (unsigned int i=0; i<3; i++) { 00269 n += operator()(i) * operator()(i); 00270 } 00271 return sqrt(n); 00272 } 00273 00274 DEPRECATED( double norm2 () const ) { // replaced by norm() 00275 return norm(); 00276 } 00277 00278 inline Vector3& normalize () { 00279 double len = norm (); 00280 if (len > 0) 00281 *this /= (float) len; 00282 return *this; 00283 } 00284 00285 inline Vector3 normalized () const { 00286 Vector3 result(*this); 00287 result.normalize (); 00288 return result; 00289 } 00290 00291 DEPRECATED( inline Vector3 unit () const ) { // replaced by normalized() 00292 return normalized(); 00293 } 00294 00295 00296 inline double angleTo(const Vector3& other) const { 00297 double dot_prod = this->dot(other); 00298 double len1 = this->norm(); 00299 double len2 = other.norm(); 00300 return acos(dot_prod / (len1*len2)); 00301 } 00302 00303 00304 inline double distance (const Vector3& other) const { 00305 double dist_x = x() - other.x(); 00306 double dist_y = y() - other.y(); 00307 double dist_z = z() - other.z(); 00308 return sqrt(dist_x*dist_x + dist_y*dist_y + dist_z*dist_z); 00309 } 00310 00311 inline double distanceXY (const Vector3& other) const { 00312 double dist_x = x() - other.x(); 00313 double dist_y = y() - other.y(); 00314 return sqrt(dist_x*dist_x + dist_y*dist_y); 00315 } 00316 00317 Vector3& rotate_IP (double roll, double pitch, double yaw); 00318 00319 // void read (unsigned char * src, unsigned int size); 00320 std::istream& read(std::istream &s); 00321 std::ostream& write(std::ostream &s) const; 00322 std::istream& readBinary(std::istream &s); 00323 std::ostream& writeBinary(std::ostream &s) const; 00324 00325 00326 protected: 00327 float data[3]; 00328 00329 }; 00330 00331 00333 std::ostream& operator<<(std::ostream& out, octomath::Vector3 const& v); 00334 00335 } 00336 00337 00338 #endif