mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AHRS_DCM: fix compile warnings re float constants
Also fix example sketch
This commit is contained in:
parent
f4bfc12316
commit
e28c555889
@ -268,7 +268,7 @@ AP_AHRS_DCM::yaw_error_compass(void)
|
||||
rb.normalize();
|
||||
if (rb.is_inf()) {
|
||||
// not a valid vector
|
||||
return 0.0;
|
||||
return 0.0f;
|
||||
}
|
||||
|
||||
// update vector holding earths magnetic field (if required)
|
||||
|
@ -55,8 +55,8 @@ public:
|
||||
|
||||
// these are experimentally derived from the simulator
|
||||
// with large drift levels
|
||||
_ki = 0.0087;
|
||||
_ki_yaw = 0.01;
|
||||
_ki = 0.0087f;
|
||||
_ki_yaw = 0.01f;
|
||||
}
|
||||
|
||||
// return the smoothed gyro vector corrected for drift
|
||||
|
@ -124,7 +124,7 @@ void loop(void)
|
||||
ToDeg(drift.x),
|
||||
ToDeg(drift.y),
|
||||
ToDeg(drift.z),
|
||||
compass.use_for_yaw() ? ToDeg(heading) : 0.0,
|
||||
compass.use_for_yaw() ? ToDeg(heading) : 0.0f,
|
||||
(1.0e6*counter)/(now-last_print));
|
||||
last_print = now;
|
||||
counter = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user