From 65e4a4ab9442afedf91696e10ea7b5a88b822d00 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Fri, 6 Nov 2015 14:11:22 +1100 Subject: [PATCH] AP_NavEKF2: Use correct casting of integers when printing Changes in response to review comments --- libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp index ac0eaadcba..793c71f5e2 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp @@ -123,7 +123,7 @@ void NavEKF2_core::setAidingMode() stateStruct.position.z = -meaHgtAtTakeOff; } else if (frontend->_fusionModeGPS == 3) { // We have commenced aiding, but GPS useage has been prohibited so use optical flow only - hal.console->printf("EKF2 IMU%i is using optical flow\n",imu_index); + hal.console->printf("EKF2 IMU%u is using optical flow\n",(unsigned)imu_index); PV_AidingMode = AID_RELATIVE; // we have optical flow data and can estimate all vehicle states posTimeout = true; velTimeout = true; @@ -133,7 +133,7 @@ void NavEKF2_core::setAidingMode() prevFlowFuseTime_ms = imuSampleTime_ms; } else { // We have commenced aiding and GPS useage is allowed - hal.console->printf("EKF2 IMU%i is using GPS\n",imu_index); + hal.console->printf("EKF2 IMU%u is using GPS\n",(unsigned)imu_index); PV_AidingMode = AID_ABSOLUTE; // we have GPS data and can estimate all vehicle states posTimeout = false; velTimeout = false; @@ -169,7 +169,7 @@ void NavEKF2_core::checkAttitudeAlignmentStatus() tiltErrFilt = alpha*temp + (1.0f-alpha)*tiltErrFilt; if (tiltErrFilt < 0.005f && !tiltAlignComplete) { tiltAlignComplete = true; - hal.console->printf("EKF2 IMU%i tilt alignment complete\n",imu_index); + hal.console->printf("EKF2 IMU%u tilt alignment complete\n",(unsigned)imu_index); } // Once tilt has converged, align yaw using magnetic field measurements @@ -179,7 +179,7 @@ void NavEKF2_core::checkAttitudeAlignmentStatus() stateStruct.quat = calcQuatAndFieldStates(eulerAngles.x, eulerAngles.y); StoreQuatReset(); yawAlignComplete = true; - hal.console->printf("EKF2 IMU%i yaw alignment complete\n",imu_index); + hal.console->printf("EKF2 IMU%u yaw alignment complete\n",(unsigned)imu_index); } } @@ -244,7 +244,7 @@ void NavEKF2_core::setOrigin() // define Earth rotation vector in the NED navigation frame at the origin calcEarthRateNED(earthRateNED, _ahrs->get_home().lat); validOrigin = true; - hal.console->printf("EKF2 IMU%i Origin Set\n",imu_index); + hal.console->printf("EKF2 IMU%u Origin Set\n",(unsigned)imu_index); } // Commands the EKF to not use GPS.