mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Math - initialise vector2 and vector3 x,y,z values to zero. Doug found (and I confirmed) that if vectors or matrices were declared in a function (i.e. a local variable), they would often have non-zero values. Global declarations don't have this problem - it's a C++ performance thing it seems.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@878 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
e7eda28984
commit
e930dacb4d
@ -32,7 +32,7 @@ struct Vector2
|
||||
|
||||
|
||||
// trivial ctor
|
||||
Vector2<T>() {}
|
||||
Vector2<T>(): x(0),y(0) {}
|
||||
|
||||
// setting ctor
|
||||
Vector2<T>(const T x0, const T y0): x(x0), y(y0) {}
|
||||
|
@ -50,7 +50,7 @@ public:
|
||||
T x, y, z;
|
||||
|
||||
// trivial ctor
|
||||
Vector3<T>() {}
|
||||
Vector3<T>(): x(0),y(0),z(0) {}
|
||||
|
||||
// setting ctor
|
||||
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