Browse Source

AHRS_DCM: fix compile warnings re float constants

Also fix example sketch
master
Tom Pittenger 10 years ago committed by Randy Mackay
parent
commit
e28c555889
  1. 2
      libraries/AP_AHRS/AP_AHRS_DCM.cpp
  2. 4
      libraries/AP_AHRS/AP_AHRS_DCM.h
  3. 2
      libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.pde

2
libraries/AP_AHRS/AP_AHRS_DCM.cpp

@ -268,7 +268,7 @@ AP_AHRS_DCM::yaw_error_compass(void) @@ -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)

4
libraries/AP_AHRS/AP_AHRS_DCM.h

@ -55,8 +55,8 @@ public: @@ -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

2
libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.pde

@ -124,7 +124,7 @@ void loop(void) @@ -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…
Cancel
Save