Browse Source

Back out the memset optimisation. It helps with code size but causes inexplicable link-time failures (undefined references to __cxa_pure_virtual).

Thank you very much Mr GCC.  Can I have my evening back?


git-svn-id: https://arducopter.googlecode.com/svn/trunk@1352 f9c3cf11-9bcb-44bc-f272-b75c42450872
mission-4.1.18
DrZiplok@gmail.com 14 years ago
parent
commit
75e78dabae
  1. 2
      libraries/AP_Math/vector2.h
  2. 2
      libraries/AP_Math/vector3.h

2
libraries/AP_Math/vector2.h

@ -31,7 +31,7 @@ struct Vector2 @@ -31,7 +31,7 @@ struct Vector2
T x, y;
// trivial ctor
Vector2<T>() {memset(this, 0, sizeof(*this));}
Vector2<T>() { x = y = 0; }
// setting ctor
Vector2<T>(const T x0, const T y0): x(x0), y(y0) {}

2
libraries/AP_Math/vector3.h

@ -51,7 +51,7 @@ public: @@ -51,7 +51,7 @@ public:
T x, y, z;
// trivial ctor
Vector3<T>() {memset(this, 0, sizeof(*this));}
Vector3<T>() { x = y = x = 0; }
// setting ctor
Vector3<T>(const T x0, const T y0, const T z0): x(x0), y(y0), z(z0) {}

Loading…
Cancel
Save