mirror of https://github.com/ArduPilot/ardupilot
added downcasting to MATRIX3_CTORS. this fixes some problems with setting the results from a formula to a variable (i..e m1 = m2*2).
git-svn-id: https://arducopter.googlecode.com/svn/trunk@541 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
b3e1b6c57d
commit
15e6469ca9
|
@ -125,6 +125,8 @@ public:
|
|||
#define MATRIX3_CTORS(name, type) \
|
||||
/* trivial ctor */ \
|
||||
name() {} \
|
||||
/* down casting ctor */ \
|
||||
name(const Matrix3<type> &m): Matrix3<type>(m.a, m.b, m.c) {} \
|
||||
/* make a,b,c combination into a matrix */ \
|
||||
name(const Vector3<type> &a0, const Vector3<type> &b0, const Vector3<type> &c0) : Matrix3<type>(a0, b0, c0) {}
|
||||
|
||||
|
|
Loading…
Reference in New Issue