mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
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
This commit is contained in:
parent
a446389c8e
commit
75e78dabae
@ -31,7 +31,7 @@ struct Vector2
|
|||||||
T x, y;
|
T x, y;
|
||||||
|
|
||||||
// trivial ctor
|
// trivial ctor
|
||||||
Vector2<T>() {memset(this, 0, sizeof(*this));}
|
Vector2<T>() { x = y = 0; }
|
||||||
|
|
||||||
// setting ctor
|
// setting ctor
|
||||||
Vector2<T>(const T x0, const T y0): x(x0), y(y0) {}
|
Vector2<T>(const T x0, const T y0): x(x0), y(y0) {}
|
||||||
|
@ -51,7 +51,7 @@ public:
|
|||||||
T x, y, z;
|
T x, y, z;
|
||||||
|
|
||||||
// trivial ctor
|
// trivial ctor
|
||||||
Vector3<T>() {memset(this, 0, sizeof(*this));}
|
Vector3<T>() { x = y = x = 0; }
|
||||||
|
|
||||||
// setting ctor
|
// setting ctor
|
||||||
Vector3<T>(const T x0, const T y0, const T z0): x(x0), y(y0), z(z0) {}
|
Vector3<T>(const T x0, const T y0, const T z0): x(x0), y(y0), z(z0) {}
|
||||||
|
Loading…
Reference in New Issue
Block a user