From b006aa61796f9d0a748c352a51ec44fc13d2d571 Mon Sep 17 00:00:00 2001 From: "DrZiplok@gmail.com" Date: Wed, 29 Dec 2010 03:09:29 +0000 Subject: [PATCH] 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 --- libraries/AP_Math/vector2.h | 2 +- libraries/AP_Math/vector3.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Math/vector2.h b/libraries/AP_Math/vector2.h index e87ac40fcd..ba00110a3f 100644 --- a/libraries/AP_Math/vector2.h +++ b/libraries/AP_Math/vector2.h @@ -31,7 +31,7 @@ struct Vector2 T x, y; // trivial ctor - Vector2() {memset(this, 0, sizeof(*this));} + Vector2() { x = y = 0; } // setting ctor Vector2(const T x0, const T y0): x(x0), y(y0) {} diff --git a/libraries/AP_Math/vector3.h b/libraries/AP_Math/vector3.h index 214928896a..35c375917a 100644 --- a/libraries/AP_Math/vector3.h +++ b/libraries/AP_Math/vector3.h @@ -51,7 +51,7 @@ public: T x, y, z; // trivial ctor - Vector3() {memset(this, 0, sizeof(*this));} + Vector3() { x = y = x = 0; } // setting ctor Vector3(const T x0, const T y0, const T z0): x(x0), y(y0), z(z0) {}