From 290635b3540b927ffb9f65d1c9d479dad050b21c Mon Sep 17 00:00:00 2001 From: "DrZiplok@gmail.com" Date: Mon, 20 Dec 2010 01:52:23 +0000 Subject: [PATCH] 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 --- libraries/AP_Math/matrix3.h | 1 + libraries/AP_Math/vector2.h | 7 +++---- libraries/AP_Math/vector3.h | 7 ++++--- 3 files changed, 8 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Math/matrix3.h b/libraries/AP_Math/matrix3.h index 51fd144c75..85f4516607 100644 --- a/libraries/AP_Math/matrix3.h +++ b/libraries/AP_Math/matrix3.h @@ -42,6 +42,7 @@ public: Vector3 a, b, c; // trivial ctor + // note that the Vector3 ctor will zero the vector elements Matrix3() {} // setting ctor diff --git a/libraries/AP_Math/vector2.h b/libraries/AP_Math/vector2.h index 9e12b524bf..e87ac40fcd 100644 --- a/libraries/AP_Math/vector2.h +++ b/libraries/AP_Math/vector2.h @@ -30,9 +30,8 @@ struct Vector2 { T x, y; - // trivial ctor - Vector2(): x(0),y(0) {} + Vector2() {memset(this, 0, sizeof(*this));} // setting ctor Vector2(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 &v1, const Vector2 &v2) + T angle(const Vector2 &v1, const Vector2 &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 &v1, const Vector2 &v2) + T angle_normalized(const Vector2 &v1, const Vector2 &v2) { return (T)acosf(v1*v2); } }; diff --git a/libraries/AP_Math/vector3.h b/libraries/AP_Math/vector3.h index 39d9e31081..214928896a 100644 --- a/libraries/AP_Math/vector3.h +++ b/libraries/AP_Math/vector3.h @@ -42,6 +42,7 @@ #define VECTOR3_H #include +#include template class Vector3 @@ -50,7 +51,7 @@ public: T x, y, z; // trivial ctor - Vector3(): x(0),y(0),z(0) {} + Vector3() {memset(this, 0, sizeof(*this));} // setting ctor Vector3(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 &v1, const Vector3 &v2) + T angle(const Vector3 &v1, const Vector3 &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 &v1, const Vector3 &v2) + T angle_normalized(const Vector3 &v1, const Vector3 &v2) { return (T)acosf(v1*v2); } };