mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 00:43:58 -04:00
Minor code size optimisation; use memset to zero *this rather than explicitly assigning zero to the vector elements. Still not quite optimal for matrix3 as it gets three memsets, but still cheaper in terms of code size.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1212 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
47bb4d22c6
commit
290635b354
@ -42,6 +42,7 @@ public:
|
||||
Vector3<T> a, b, c;
|
||||
|
||||
// trivial ctor
|
||||
// note that the Vector3 ctor will zero the vector elements
|
||||
Matrix3<T>() {}
|
||||
|
||||
// setting ctor
|
||||
|
@ -30,9 +30,8 @@ struct Vector2
|
||||
{
|
||||
T x, y;
|
||||
|
||||
|
||||
// trivial ctor
|
||||
Vector2<T>(): x(0),y(0) {}
|
||||
Vector2<T>() {memset(this, 0, sizeof(*this));}
|
||||
|
||||
// setting ctor
|
||||
Vector2<T>(const T x0, const T y0): x(x0), y(y0) {}
|
||||
@ -140,11 +139,11 @@ struct Vector2
|
||||
{ return v * (*this * v)/(v*v); }
|
||||
|
||||
// computes the angle between 2 arbitrary vectors
|
||||
static inline T angle(const Vector2<T> &v1, const Vector2<T> &v2)
|
||||
T angle(const Vector2<T> &v1, const Vector2<T> &v2)
|
||||
{ return (T)acosf((v1*v2) / (v1.length()*v2.length())); }
|
||||
|
||||
// computes the angle between 2 normalized arbitrary vectors
|
||||
static inline T angle_normalized(const Vector2<T> &v1, const Vector2<T> &v2)
|
||||
T angle_normalized(const Vector2<T> &v1, const Vector2<T> &v2)
|
||||
{ return (T)acosf(v1*v2); }
|
||||
|
||||
};
|
||||
|
@ -42,6 +42,7 @@
|
||||
#define VECTOR3_H
|
||||
|
||||
#include <math.h>
|
||||
#include <string.h>
|
||||
|
||||
template <typename T>
|
||||
class Vector3
|
||||
@ -50,7 +51,7 @@ public:
|
||||
T x, y, z;
|
||||
|
||||
// trivial ctor
|
||||
Vector3<T>(): x(0),y(0),z(0) {}
|
||||
Vector3<T>() {memset(this, 0, sizeof(*this));}
|
||||
|
||||
// setting ctor
|
||||
Vector3<T>(const T x0, const T y0, const T z0): x(x0), y(y0), z(z0) {}
|
||||
@ -165,11 +166,11 @@ public:
|
||||
{ return v * (*this * v)/(v*v); }
|
||||
|
||||
// computes the angle between 2 arbitrary vectors
|
||||
static inline T angle(const Vector3<T> &v1, const Vector3<T> &v2)
|
||||
T angle(const Vector3<T> &v1, const Vector3<T> &v2)
|
||||
{ return (T)acosf((v1*v2) / (v1.length()*v2.length())); }
|
||||
|
||||
// computes the angle between 2 arbitrary normalized vectors
|
||||
static inline T angle_normalized(const Vector3<T> &v1, const Vector3<T> &v2)
|
||||
T angle_normalized(const Vector3<T> &v1, const Vector3<T> &v2)
|
||||
{ return (T)acosf(v1*v2); }
|
||||
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user