mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Math: define Vector3l for += op
This commit is contained in:
parent
565f1986e0
commit
b00fd95725
@ -390,7 +390,7 @@ Matrix3<T> Vector3<T>::mul_rowcol(const Vector3<T> &v2) const
|
||||
v1.z * v2.x, v1.z * v2.y, v1.z * v2.z);
|
||||
}
|
||||
|
||||
// only define for float
|
||||
// define for float
|
||||
template void Vector3<float>::rotate(enum Rotation);
|
||||
template void Vector3<float>::rotate_inverse(enum Rotation);
|
||||
template float Vector3<float>::length(void) const;
|
||||
@ -413,6 +413,9 @@ template bool Vector3<float>::is_nan(void) const;
|
||||
template bool Vector3<float>::is_inf(void) const;
|
||||
template float Vector3<float>::angle(const Vector3<float> &v) const;
|
||||
|
||||
// define needed ops for Vector3l
|
||||
template Vector3<int32_t> &Vector3<int32_t>::operator +=(const Vector3<int32_t> &v);
|
||||
|
||||
template void Vector3<double>::rotate(enum Rotation);
|
||||
template void Vector3<double>::rotate_inverse(enum Rotation);
|
||||
template float Vector3<double>::length(void) const;
|
||||
|
Loading…
Reference in New Issue
Block a user