mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_InertialSensor: replace sqrt with safe_sqrt to resolve compiler warning
Also add suppressing comment for missing break at end of switch
This commit is contained in:
parent
82322144ee
commit
081beacb8d
@ -1334,7 +1334,7 @@ void AP_InertialSensor::_acal_save_calibrations()
|
||||
// determine trim from aligned sample vs misaligned sample
|
||||
Vector3f cross = (misaligned_sample%aligned_sample);
|
||||
float dot = (misaligned_sample*aligned_sample);
|
||||
Quaternion q(sqrt(sq(misaligned_sample.length())*sq(aligned_sample.length()))+dot, cross.x, cross.y, cross.z);
|
||||
Quaternion q(safe_sqrt(sq(misaligned_sample.length())*sq(aligned_sample.length()))+dot, cross.x, cross.y, cross.z);
|
||||
q.normalize();
|
||||
_trim_roll = q.get_euler_roll();
|
||||
_trim_pitch = q.get_euler_pitch();
|
||||
@ -1343,7 +1343,7 @@ void AP_InertialSensor::_acal_save_calibrations()
|
||||
break;
|
||||
default:
|
||||
_new_trim = false;
|
||||
//noop
|
||||
/* no break */
|
||||
}
|
||||
|
||||
if (fabsf(_trim_roll) > radians(10) ||
|
||||
|
Loading…
Reference in New Issue
Block a user