Browse Source

AP_Math: fix div by zero in quaternion

master
Jonathan Challinger 10 years ago committed by Andrew Tridgell
parent
commit
07735fefa6
  1. 1
      libraries/AP_Math/quaternion.cpp

1
libraries/AP_Math/quaternion.cpp

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

Loading…
Cancel
Save