From 115e5254d92df65762c661249d9b66060d326b7e Mon Sep 17 00:00:00 2001 From: Eric Katzfey Date: Thu, 14 Nov 2024 12:23:38 -0800 Subject: [PATCH] AP_InertialSensor: Added explicit casts to get rid of Qurt compiler warning about implicit casts --- .../AP_InertialSensor/AP_InertialSensor_ADIS1647x.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_ADIS1647x.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_ADIS1647x.cpp index ddfc05eac2..adccda6023 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_ADIS1647x.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_ADIS1647x.cpp @@ -171,22 +171,22 @@ bool AP_InertialSensor_ADIS1647x::check_product_id(uint16_t &prod_id) opmode = OpMode::Delta32; expected_sample_rate_hz = 1200; accel_scale = 392.0 / 2097152000.0; - dvel_scale = 400.0 / 0x7FFFFFFF; + dvel_scale = 400.0 / (float)0x7FFFFFFF; _clip_limit = (40.0f - 0.5f) * GRAVITY_MSS; // RANG_MDL register used for gyro range uint16_t rang_mdl = read_reg16(REG_RANG_MDL); switch ((rang_mdl >> 2) & 3) { case 0: gyro_scale = radians(125) / 0x4E200000; - dangle_scale = radians(360.0 / 0x7FFFFFFF); + dangle_scale = radians(360.0 / (float)0x7FFFFFFF); break; case 1: gyro_scale = radians(500) / 0x4E200000; - dangle_scale = radians(720.0 / 0x7FFFFFFF); + dangle_scale = radians(720.0 / (float)0x7FFFFFFF); break; case 3: gyro_scale = radians(2000) / 0x4E200000; - dangle_scale = radians(2160.0 / 0x7FFFFFFF); + dangle_scale = radians(2160.0 / (float)0x7FFFFFFF); break; default: return false;