ardupilot/libraries/AP_Math/vector3.h

225 lines
5.8 KiB
C
Raw Normal View History

2013-05-29 20:51:51 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
// Copyright 2010 Michael Smith, all rights reserved.
// Derived closely from:
/****************************************
2012-08-17 03:20:14 -03:00
* 3D Vector Classes
* By Bill Perone (billperone@yahoo.com)
* Original: 9-16-2002
* Revised: 19-11-2003
* 11-12-2003
* 18-12-2003
* 06-06-2004
*
* <EFBFBD> 2003, This code is provided "as is" and you can use it freely as long as
* credit is given to Bill Perone in the application it is used in
*
* Notes:
* if a*b = 0 then a & b are orthogonal
* a%b = -b%a
* a*(b%c) = (a%b)*c
* a%b = a(cast to matrix)*b
* (a%b).length() = area of parallelogram formed by a & b
* (a%b).length() = a.length()*b.length() * sin(angle between a & b)
* (a%b).length() = 0 if angle between a & b = 0 or a.length() = 0 or b.length() = 0
* a * (b%c) = volume of parallelpiped formed by a, b, c
* vector triple product: a%(b%c) = b*(a*c) - c*(a*b)
* scalar triple product: a*(b%c) = c*(a%b) = b*(c%a)
* vector quadruple product: (a%b)*(c%d) = (a*c)*(b*d) - (a*d)*(b*c)
* if a is unit vector along b then a%b = -b%a = -b(cast to matrix)*a = 0
* vectors a1...an are linearly dependant if there exists a vector of scalars (b) where a1*b1 + ... + an*bn = 0
* or if the matrix (A) * b = 0
*
****************************************/
#ifndef VECTOR3_H
#define VECTOR3_H
#include <math.h>
#include <float.h>
#include <string.h>
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#include <assert.h>
#endif
template <typename T>
class Matrix3;
template <typename T>
class Vector3
{
public:
2012-08-17 03:20:14 -03:00
T x, y, z;
// trivial ctor
Vector3<T>() {
x = y = z = 0;
}
// setting ctor
Vector3<T>(const T x0, const T y0, const T z0) : x(x0), y(y0), z(z0) {
}
// function call operator
void operator ()(const T x0, const T y0, const T z0)
2012-08-17 03:20:14 -03:00
{
x= x0; y= y0; z= z0;
}
// test for equality
bool operator ==(const Vector3<T> &v) const;
2012-08-17 03:20:14 -03:00
// test for inequality
bool operator !=(const Vector3<T> &v) const;
2012-08-17 03:20:14 -03:00
// negation
Vector3<T> operator -(void) const;
2012-08-17 03:20:14 -03:00
// addition
Vector3<T> operator +(const Vector3<T> &v) const;
2012-08-17 03:20:14 -03:00
// subtraction
Vector3<T> operator -(const Vector3<T> &v) const;
2012-08-17 03:20:14 -03:00
// uniform scaling
Vector3<T> operator *(const T num) const;
2012-08-17 03:20:14 -03:00
// uniform scaling
Vector3<T> operator /(const T num) const;
2012-08-17 03:20:14 -03:00
// addition
Vector3<T> &operator +=(const Vector3<T> &v);
2012-08-17 03:20:14 -03:00
// subtraction
Vector3<T> &operator -=(const Vector3<T> &v);
2012-08-17 03:20:14 -03:00
// uniform scaling
Vector3<T> &operator *=(const T num);
2012-08-17 03:20:14 -03:00
// uniform scaling
Vector3<T> &operator /=(const T num);
2012-08-17 03:20:14 -03:00
// allow a vector3 to be used as an array, 0 indexed
T & operator[](uint8_t i) {
T *_v = &x;
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
assert(i >= 0 && i < 3);
#endif
return _v[i];
}
const T & operator[](uint8_t i) const {
const T *_v = &x;
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
assert(i >= 0 && i < 3);
#endif
return _v[i];
}
2012-08-17 03:20:14 -03:00
// dot product
T operator *(const Vector3<T> &v) const;
2012-08-17 03:20:14 -03:00
// multiply a row vector by a matrix, to give a row vector
Vector3<T> operator *(const Matrix3<T> &m) const;
// multiply a column vector by a row vector, returning a 3x3 matrix
Matrix3<T> mul_rowcol(const Vector3<T> &v) const;
2012-08-17 03:20:14 -03:00
// cross product
Vector3<T> operator %(const Vector3<T> &v) const;
// computes the angle between this vector and another vector
float angle(const Vector3<T> &v2) const;
// check if any elements are NAN
bool is_nan(void) const;
// check if any elements are infinity
bool is_inf(void) const;
// check if all elements are zero
bool is_zero(void) const { return (fabsf(x) < FLT_EPSILON) && (fabsf(y) < FLT_EPSILON) && (fabsf(z) < FLT_EPSILON); }
// rotate by a standard rotation
void rotate(enum Rotation rotation);
2012-08-17 03:20:14 -03:00
// gets the length of this vector squared
T length_squared() const
2012-08-17 03:20:14 -03:00
{
return (T)(*this * *this);
}
// gets the length of this vector
float length(void) const;
2012-08-17 03:20:14 -03:00
// normalizes this vector
void normalize()
2012-08-17 03:20:14 -03:00
{
*this /= length();
2012-08-17 03:20:14 -03:00
}
// zero the vector
void zero()
2012-08-17 03:20:14 -03:00
{
x = y = z = 0;
2012-08-17 03:20:14 -03:00
}
// returns the normalized version of this vector
Vector3<T> normalized() const
2012-08-17 03:20:14 -03:00
{
return *this/length();
}
// reflects this vector about n
void reflect(const Vector3<T> &n)
2012-08-17 03:20:14 -03:00
{
Vector3<T> orig(*this);
project(n);
*this = *this*2 - orig;
2012-08-17 03:20:14 -03:00
}
// projects this vector onto v
void project(const Vector3<T> &v)
2012-08-17 03:20:14 -03:00
{
*this= v * (*this * v)/(v*v);
}
// returns this vector projected onto v
Vector3<T> projected(const Vector3<T> &v) const
2012-08-17 03:20:14 -03:00
{
return v * (*this * v)/(v*v);
}
};
2012-08-17 03:20:14 -03:00
typedef Vector3<int16_t> Vector3i;
typedef Vector3<uint16_t> Vector3ui;
typedef Vector3<int32_t> Vector3l;
typedef Vector3<uint32_t> Vector3ul;
typedef Vector3<float> Vector3f;
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
typedef Vector3<double> Vector3d;
#endif
#endif // VECTOR3_H