mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_NavEKF2: Use correct casting of integers when printing
Changes in response to review comments
This commit is contained in:
parent
987d261109
commit
65e4a4ab94
@ -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.
|
||||
|
Loading…
Reference in New Issue
Block a user