AP_Math: fix div by zero in quaternion

This commit is contained in:
Jonathan Challinger 2015-04-07 20:58:20 -07:00 committed by Andrew Tridgell
parent c57e25142c
commit 07735fefa6

View File

@ -120,6 +120,7 @@ void Quaternion::from_axis_angle(Vector3f v) {
if(theta == 0.0f) { if(theta == 0.0f) {
q1 = 1.0f; q1 = 1.0f;
q2=q3=q4=0.0f; q2=q3=q4=0.0f;
return;
} }
v /= theta; v /= theta;
from_axis_angle(v,theta); from_axis_angle(v,theta);