Fix Accelerometer scale in ADIS16470 driver
The accelerometer scalar didn't match the datasheet, and was resulting
in acceleration measurements being 4% too small.
Change-Id: I63355053d8fe21b3298389983d1798ff7094465b
diff --git a/frc971/wpilib/ADIS16470.cc b/frc971/wpilib/ADIS16470.cc
index c42e964..b558202 100644
--- a/frc971/wpilib/ADIS16470.cc
+++ b/frc971/wpilib/ADIS16470.cc
@@ -159,7 +159,7 @@
constexpr double kGyroLsbRadianSecond =
1.0 / 10.0 * (2.0 * M_PI / 360.0) /* degrees -> radians */;
// G/LSB for the accelerometers (for the full 32-bit value).
-constexpr double kAccelerometerLsbG = 1.0 / 54'428'800.0;
+constexpr double kAccelerometerLsbG = 1.0 / 52'428'800.0;
// C/LSB for the temperature.
constexpr double kTemperatureLsbDegree = 0.1;