mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: minor comment fix
This commit is contained in:
parent
e9426b2ff3
commit
61c4643aed
|
@ -706,7 +706,7 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = {
|
|||
|
||||
// @Param: GND_EFF_DZ
|
||||
// @DisplayName: Baro height ground effect dead zone
|
||||
// @Description: This parameter sets the size of the dead zone that is applied to negative baro height spikes that can occur when takeing off or landing when a vehicle with lift rotors is operating in ground effect ground effect. Set to about 0.5m less than the amount of negative offset in baro height that occurs just prior to takeoff when lift motors are spooling up. Set to 0 if no ground effect is present.
|
||||
// @Description: This parameter sets the size of the dead zone that is applied to negative baro height spikes that can occur when taking off or landing when a vehicle with lift rotors is operating in ground effect ground effect. Set to about 0.5m less than the amount of negative offset in baro height that occurs just prior to takeoff when lift motors are spooling up. Set to 0 if no ground effect is present.
|
||||
// @Range: 0.0 10.0
|
||||
// @Increment: 0.5
|
||||
// @User: Advanced
|
||||
|
|
|
@ -461,7 +461,7 @@ private:
|
|||
const uint8_t flowIntervalMin_ms = 20; // The minimum allowed time between measurements from optical flow sensors (msec)
|
||||
const uint8_t extNavIntervalMin_ms = 20; // The minimum allowed time between measurements from external navigation sensors (msec)
|
||||
const float maxYawEstVelInnov = 2.0f; // Maximum acceptable length of the velocity innovation returned by the EKF-GSF yaw estimator (m/s)
|
||||
const uint16_t deadReckonDeclare_ms = 1000; // Time without equivalent position or velocity observation to constrain drift beore dead reckoning is declared (msec)
|
||||
const uint16_t deadReckonDeclare_ms = 1000; // Time without equivalent position or velocity observation to constrain drift before dead reckoning is declared (msec)
|
||||
|
||||
// time at start of current filter update
|
||||
uint64_t imuSampleTime_us;
|
||||
|
|
|
@ -254,7 +254,7 @@ void NavEKF3_core::SelectBetaDragFusion()
|
|||
// we are required to correct all states
|
||||
airDataFusionWindOnly = false;
|
||||
} else {
|
||||
// we are required to corrrect only wind states
|
||||
// we are required to correct only wind states
|
||||
airDataFusionWindOnly = true;
|
||||
}
|
||||
// Fuse estimated airspeed to aid wind estimation
|
||||
|
@ -529,7 +529,7 @@ void NavEKF3_core::FuseDragForces()
|
|||
// correct accel data for bias
|
||||
const ftype mea_acc = dragSampleDelayed.accelXY[axis_index] - stateStruct.accel_bias[axis_index] / dtEkfAvg;
|
||||
|
||||
// Acceleration in m/s/s predicfed using vehicle and wind velocity estimates
|
||||
// Acceleration in m/s/s predicted using vehicle and wind velocity estimates
|
||||
// Initialised to measured value and updated later using available drag model
|
||||
ftype predAccel = mea_acc;
|
||||
|
||||
|
@ -620,7 +620,7 @@ void NavEKF3_core::FuseDragForces()
|
|||
|
||||
|
||||
} else if (axis_index == 1) {
|
||||
// drag can be modelled as an arbitrary combination of bluff body drag that proportional to
|
||||
// drag can be modelled as an arbitrary combination of bluff body drag that proportional to
|
||||
// speed squared, and rotor momentum drag that is proportional to speed.
|
||||
ftype Kacc; // Derivative of specific force wrt airspeed
|
||||
if (using_mcoef && using_bcoef_y) {
|
||||
|
|
Loading…
Reference in New Issue