AP_NavEKF: Fix typos
This commit is contained in:
parent
4047fb63fc
commit
267a74ebb2
@ -127,7 +127,7 @@ const AP_Param::GroupInfo NavEKF::var_info[] = {
|
||||
|
||||
// @Param: VELNE_NOISE
|
||||
// @DisplayName: GPS horizontal velocity measurement noise scaler
|
||||
// @Description: This is the scaler that is applied to the speed accuracy reported by the receiver to estimate the horizontal velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then a speed acuracy of 1 is assumed. Increasing it reduces the weighting on these measurements.
|
||||
// @Description: This is the scaler that is applied to the speed accuracy reported by the receiver to estimate the horizontal velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then a speed accuracy of 1 is assumed. Increasing it reduces the weighting on these measurements.
|
||||
// @Range: 0.05 5.0
|
||||
// @Increment: 0.05
|
||||
// @User: Advanced
|
||||
@ -135,7 +135,7 @@ const AP_Param::GroupInfo NavEKF::var_info[] = {
|
||||
|
||||
// @Param: VELD_NOISE
|
||||
// @DisplayName: GPS vertical velocity measurement noise scaler
|
||||
// @Description: This is the scaler that is applied to the speed accuracy reported by the receiver to estimate the vertical velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then a speed acuracy of 1 is assumed. Increasing it reduces the weighting on this measurement.
|
||||
// @Description: This is the scaler that is applied to the speed accuracy reported by the receiver to estimate the vertical velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then a speed accuracy of 1 is assumed. Increasing it reduces the weighting on this measurement.
|
||||
// @Range: 0.05 5.0
|
||||
// @Increment: 0.05
|
||||
// @User: Advanced
|
||||
@ -333,7 +333,7 @@ const AP_Param::GroupInfo NavEKF::var_info[] = {
|
||||
|
||||
// @Param: GND_GRADIENT
|
||||
// @DisplayName: Terrain Gradient % RMS
|
||||
// @Description: This parameter sets the RMS terrain gradient percentage assumed by the terrain height estimation. Terrain height can be estimated using optical flow and/or range finder sensor data if fitted. Smaller values cause the terrain height estimate to be slower to respond to changes in measurement. Larger values casue the terrain height estimate to be faster to respond, but also more noisy. Generally this value can be reduced if operating over very flat terrain and increased if operating over uneven terrain.
|
||||
// @Description: This parameter sets the RMS terrain gradient percentage assumed by the terrain height estimation. Terrain height can be estimated using optical flow and/or range finder sensor data if fitted. Smaller values cause the terrain height estimate to be slower to respond to changes in measurement. Larger values cause the terrain height estimate to be faster to respond, but also more noisy. Generally this value can be reduced if operating over very flat terrain and increased if operating over uneven terrain.
|
||||
// @Range: 1 50
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
@ -390,7 +390,7 @@ const AP_Param::GroupInfo NavEKF::var_info[] = {
|
||||
|
||||
// @Param: ALT_SOURCE
|
||||
// @DisplayName: Primary height source
|
||||
// @Description: This parameter controls which height sensor is used by the EKF during optical flow navigation (when EKF_GPS_TYPE = 3). A value of will 0 cause it to always use baro altitude. A value of 1 will casue it to use range finder if available.
|
||||
// @Description: This parameter controls which height sensor is used by the EKF during optical flow navigation (when EKF_GPS_TYPE = 3). A value of will 0 cause it to always use baro altitude. A value of 1 will cause it to use range finder if available.
|
||||
// @Values: 0:Use Baro, 1:Use Range Finder
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ALT_SOURCE", 32, NavEKF, _altSource, 1),
|
||||
|
@ -501,7 +501,7 @@ void NavEKF_core::SelectVelPosFusion()
|
||||
velTimeout = true;
|
||||
// If this happens in flight and we don't have airspeed or sideslip assumption or optical flow to constrain drift, then go into constant position mode.
|
||||
// Stay in that mode until the vehicle is re-armed.
|
||||
// If we can do optical flow nav (valid flow data and hieght above ground estimate, then go into flow nav mode.
|
||||
// If we can do optical flow nav (valid flow data and height above ground estimate, then go into flow nav mode.
|
||||
// Stay in that mode until the vehicle is dis-armed.
|
||||
if (vehicleArmed && !useAirspeed() && !assume_zero_sideslip()) {
|
||||
if (optFlowBackup) {
|
||||
@ -881,7 +881,7 @@ void NavEKF_core::UpdateStrapdownEquationsNED()
|
||||
accNavMag = velDotNEDfilt.length();
|
||||
accNavMagHoriz = norm(velDotNEDfilt.x , velDotNEDfilt.y);
|
||||
|
||||
// save velocity for use in trapezoidal intergration for position calcuation
|
||||
// save velocity for use in trapezoidal integration for position calcuation
|
||||
Vector3f lastVelocity = state.velocity;
|
||||
Vector3f lastVel1 = state.vel1;
|
||||
Vector3f lastVel2 = state.vel2;
|
||||
@ -2344,7 +2344,7 @@ void NavEKF_core::FuseMagnetometer()
|
||||
// Attitude, velocity and position corrections are averaged across multiple prediction cycles between now and the anticipated time for the next measurement.
|
||||
// Don't do averaging of quaternion state corrections if total angle change across predicted interval is going to exceed 0.1 rad
|
||||
bool highRates = ((magUpdateCountMax * correctedDelAng.length()) > 0.1f);
|
||||
// Calculate the number of averaging frames left to go. This is required becasue magnetometer fusion is applied across three consecutive prediction cycles
|
||||
// Calculate the number of averaging frames left to go. This is required because magnetometer fusion is applied across three consecutive prediction cycles
|
||||
// There is no point averaging if the number of cycles left is less than 2
|
||||
float minorFramesToGo = float(magUpdateCountMax) - float(magUpdateCount);
|
||||
// correct the state vector or store corrections to be applied incrementally
|
||||
@ -2358,7 +2358,7 @@ void NavEKF_core::FuseMagnetometer()
|
||||
if (vehicleArmed && (constPosMode || highYawRate) && j <= 3) {
|
||||
Kfusion[j] *= 4.0f;
|
||||
}
|
||||
// We don't need to spread corrections for non-dynamic states or if we are in a constant postion mode
|
||||
// We don't need to spread corrections for non-dynamic states or if we are in a constant position mode
|
||||
// We can't spread corrections if there is not enough time remaining
|
||||
// We don't spread corrections to attitude states if we are rotating rapidly
|
||||
if ((j <= 3 && highRates) || j >= 10 || constPosMode || minorFramesToGo < 1.5f ) {
|
||||
@ -3551,7 +3551,7 @@ bool NavEKF_core::getLLH(struct Location &loc) const
|
||||
location_offset(loc, state.position.x, state.position.y);
|
||||
return true;
|
||||
} else {
|
||||
// we could be in constant position mode becasue the vehicle has taken off without GPS, or has lost GPS
|
||||
// we could be in constant position mode because the vehicle has taken off without GPS, or has lost GPS
|
||||
// in this mode we cannot use the EKF states to estimate position so will return the best available data
|
||||
if ((_ahrs->get_gps().status() >= AP_GPS::GPS_OK_FIX_2D)) {
|
||||
// we have a GPS position fix to return
|
||||
@ -4738,7 +4738,7 @@ void NavEKF_core::performArmingChecks()
|
||||
heldVelNE.zero();
|
||||
// reset the flag that indicates takeoff for use by optical flow navigation
|
||||
takeOffDetected = false;
|
||||
// set various useage modes based on the condition at arming. These are then held until the vehicle is disarmed.
|
||||
// set various usage modes based on the condition at arming. These are then held until the vehicle is disarmed.
|
||||
if (!vehicleArmed) {
|
||||
PV_AidingMode = AID_NONE; // When dis-armed, we only estimate orientation & height using the constant position mode
|
||||
posTimeout = true;
|
||||
@ -4764,7 +4764,7 @@ void NavEKF_core::performArmingChecks()
|
||||
gpsDriftNE = 0.0f;
|
||||
gpsVertVelFilt = 0.0f;
|
||||
gpsHorizVelFilt = 0.0f;
|
||||
} else if (frontend._fusionModeGPS == 3) { // arming when GPS useage has been prohibited
|
||||
} else if (frontend._fusionModeGPS == 3) { // arming when GPS usage has been prohibited
|
||||
if (optFlowDataPresent()) {
|
||||
PV_AidingMode = AID_RELATIVE; // we have optical flow data and can estimate all vehicle states
|
||||
posTimeout = true;
|
||||
@ -4780,13 +4780,13 @@ void NavEKF_core::performArmingChecks()
|
||||
flowValidMeaTime_ms = imuSampleTime_ms;
|
||||
// Reset the last valid flow fusion time
|
||||
prevFlowFuseTime_ms = imuSampleTime_ms;
|
||||
// this avoids issues casued by the time delay associated with arming that can trigger short timeouts
|
||||
// this avoids issues caused by the time delay associated with arming that can trigger short timeouts
|
||||
rngValidMeaTime_ms = imuSampleTime_ms;
|
||||
// store the range finder measurement which will be used as a reference to detect when we have taken off
|
||||
rangeAtArming = rngMea;
|
||||
// set the time at which we arm to assist with takeoff detection
|
||||
timeAtArming_ms = imuSampleTime_ms;
|
||||
} else { // arming when GPS useage is allowed
|
||||
} else { // arming when GPS usage is allowed
|
||||
if (gpsNotAvailable) {
|
||||
PV_AidingMode = AID_NONE; // we don't have have GPS data and will only be able to estimate orientation and height
|
||||
posTimeout = true;
|
||||
@ -4798,7 +4798,7 @@ void NavEKF_core::performArmingChecks()
|
||||
velTimeout = false;
|
||||
constPosMode = false;
|
||||
// we need to reset the GPS timers to prevent GPS timeout logic being invoked on entry into GPS aiding
|
||||
// this is becasue the EKF can be interrupted for an arbitrary amount of time during vehicle arming checks
|
||||
// this is because the EKF can be interrupted for an arbitrary amount of time during vehicle arming checks
|
||||
lastFixTime_ms = imuSampleTime_ms;
|
||||
secondLastFixTime_ms = imuSampleTime_ms;
|
||||
// reset the last valid position fix time to prevent unwanted activation of GPS glitch logic
|
||||
@ -4809,12 +4809,12 @@ void NavEKF_core::performArmingChecks()
|
||||
}
|
||||
if (vehicleArmed) {
|
||||
// Reset filter position to GPS when transitioning into flight mode
|
||||
// We need to do this becasue the vehicle may have moved since the EKF origin was set
|
||||
// We need to do this because the vehicle may have moved since the EKF origin was set
|
||||
ResetPosition();
|
||||
StoreStatesReset();
|
||||
} else {
|
||||
// Reset all position and velocity states when transitioning out of flight mode
|
||||
// We need to do this becasue we are going into a mode that assumes zero position and velocity
|
||||
// We need to do this because we are going into a mode that assumes zero position and velocity
|
||||
ResetVelocity();
|
||||
ResetPosition();
|
||||
StoreStatesReset();
|
||||
@ -4901,7 +4901,7 @@ void NavEKF_core::setTouchdownExpected(bool val)
|
||||
Monitor GPS data to see if quality is good enough to initialise the EKF
|
||||
Monitor magnetometer innovations to to see if the heading is good enough to use GPS
|
||||
Return true if all criteria pass for 10 seconds
|
||||
Once we have set the origin and are operating in GPS mode the status is set to true to avoid a race conditon with remote useage
|
||||
Once we have set the origin and are operating in GPS mode the status is set to true to avoid a race conditon with remote usage
|
||||
If we have landed with good GPS, then the status is assumed good for 5 seconds to allow transients to settle
|
||||
|
||||
We also record the failure reason so that prearm_failure_reason() can give a good report to the user on why arming is failing
|
||||
|
@ -635,7 +635,7 @@ private:
|
||||
uint8_t storeIndex; // State vector storage index
|
||||
uint32_t lastStateStoreTime_ms; // time of last state vector storage
|
||||
uint32_t lastFixTime_ms; // time of last GPS fix used to determine if new data has arrived
|
||||
uint32_t timeAtLastAuxEKF_ms; // last time the auxilliary filter was run to fuse range or optical flow measurements
|
||||
uint32_t timeAtLastAuxEKF_ms; // last time the auxiliary filter was run to fuse range or optical flow measurements
|
||||
uint32_t secondLastFixTime_ms; // time of second last GPS fix used to determine how long since last update
|
||||
uint32_t lastHealthyMagTime_ms; // time the magnetometer was last declared healthy
|
||||
uint32_t ekfStartTime_ms; // time the EKF was started (msec)
|
||||
|
@ -115,7 +115,7 @@ nStates=numel(stateVector);
|
||||
|
||||
% Define the control (disturbance) vector. Error growth in the inertial
|
||||
% solution is assumed to be driven by 'noise' in the delta angles and
|
||||
% velocities, after bias effects have been removed. This is OK becasue we
|
||||
% velocities, after bias effects have been removed. This is OK because we
|
||||
% have sensor bias accounted for in the state equations.
|
||||
distVector = [daxNoise;dayNoise;dazNoise;dvxNoise;dvyNoise;dvzNoise];
|
||||
|
||||
|
@ -137,7 +137,7 @@ save 'symeqns.mat';
|
||||
|
||||
% Define the control (disturbance) vector. Error growth in the inertial
|
||||
% solution is assumed to be driven by 'noise' in the delta angles and
|
||||
% velocities, after bias effects have been removed. This is OK becasue we
|
||||
% velocities, after bias effects have been removed. This is OK because we
|
||||
% have sensor bias accounted for in the state equations.
|
||||
distVector = [daxNoise;dayNoise;dazNoise;dvxNoise;dvyNoise;dvzNoise];
|
||||
|
||||
|
@ -75,7 +75,7 @@ for fastIndex = 1:indexLimitFast % 1000 Hz gimbal prediction loop
|
||||
time = dtFast*fastIndex;
|
||||
% Calculate Truth Data
|
||||
% Need to replace this with a full kinematic model or test data
|
||||
% calculate truth angular rates - we don't start maneouvring until
|
||||
% calculate truth angular rates - we don't start manoeuvring until
|
||||
% heading alignment is complete
|
||||
psiRateTruth = gndSpd/radius*hdgAlignedEKF;
|
||||
angRateTruth = [0;0;psiRateTruth]; % constant yaw rate
|
||||
|
Loading…
Reference in New Issue
Block a user