AP_Math: quaternion fix missing return

This commit is contained in:
Pierre Kancir 2016-12-05 10:08:08 +01:00 committed by Lucas De Marchi
parent 3bdeac78c7
commit fb7a00799f

View File

@ -169,6 +169,7 @@ void Quaternion::from_axis_angle(const Vector3f &axis, float theta)
if (is_zero(theta)) {
q1 = 1.0f;
q2=q3=q4=0.0f;
return;
}
float st2 = sinf(theta/2.0f);
@ -201,6 +202,7 @@ void Quaternion::from_axis_angle_fast(Vector3f v)
if (is_zero(theta)) {
q1 = 1.0f;
q2=q3=q4=0.0f;
return;
}
v /= theta;
from_axis_angle_fast(v,theta);