AP_Airspeed: Fix some typos

Fixed some typos found in the code.
This commit is contained in:
Mykhailo Kuznietsov 2023-10-11 18:41:50 +11:00 committed by Peter Barker
parent 28e4f78ebb
commit fb2bf42cf6
5 changed files with 6 additions and 6 deletions

View File

@ -156,7 +156,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @Param: _OFF_PCNT // @Param: _OFF_PCNT
// @DisplayName: Maximum offset cal speed error // @DisplayName: Maximum offset cal speed error
// @Description: The maximum percentage speed change in airspeed reports that is allowed due to offset changes between calibraions before a warning is issued. This potential speed error is in percent of ASPD_FBW_MIN. 0 disables. Helps warn of calibrations without pitot being covered. // @Description: The maximum percentage speed change in airspeed reports that is allowed due to offset changes between calibrations before a warning is issued. This potential speed error is in percent of ASPD_FBW_MIN. 0 disables. Helps warn of calibrations without pitot being covered.
// @Range: 0.0 10.0 // @Range: 0.0 10.0
// @Units: % // @Units: %
// @User: Advanced // @User: Advanced
@ -632,7 +632,7 @@ void AP_Airspeed::read(uint8_t i)
if (!prev_healthy) { if (!prev_healthy) {
// if the previous state was not healthy then we should not // if the previous state was not healthy then we should not
// use an IIR filter, otherwise a bad reading will last for // use an IIR filter, otherwise a bad reading will last for
// some time after the sensor becomees healthy again // some time after the sensor becomes healthy again
state[i].filtered_pressure = airspeed_pressure; state[i].filtered_pressure = airspeed_pressure;
} else { } else {
state[i].filtered_pressure = 0.7f * state[i].filtered_pressure + 0.3f * airspeed_pressure; state[i].filtered_pressure = 0.7f * state[i].filtered_pressure + 0.3f * airspeed_pressure;

View File

@ -56,7 +56,7 @@ public:
private: private:
// state of kalman filter for airspeed ratio estimation // state of kalman filter for airspeed ratio estimation
Matrix3f P; // covarience matrix Matrix3f P; // covariance matrix
const float Q0; // process noise matrix top left and middle element const float Q0; // process noise matrix top left and middle element
const float Q1; // process noise matrix bottom right element const float Q1; // process noise matrix bottom right element
Vector3f state; // state vector Vector3f state; // state vector

View File

@ -42,7 +42,7 @@ public:
// return the current temperature in degrees C, if available // return the current temperature in degrees C, if available
virtual bool get_temperature(float &temperature) = 0; virtual bool get_temperature(float &temperature) = 0;
// true if sensor reads airspeed directly, not via pressue // true if sensor reads airspeed directly, not via pressure
virtual bool has_airspeed() {return false;} virtual bool has_airspeed() {return false;}
// return airspeed in m/s if available // return airspeed in m/s if available

View File

@ -96,7 +96,7 @@ bool AP_Airspeed_NMEA::get_airspeed(float &airspeed)
} }
// return the current temperature in degrees C // return the current temperature in degrees C
// the main update is done in the get_pressue function // the main update is done in the get_pressure function
// this just reports the value // this just reports the value
bool AP_Airspeed_NMEA::get_temperature(float &temperature) bool AP_Airspeed_NMEA::get_temperature(float &temperature)
{ {

View File

@ -261,7 +261,7 @@ float AP_Airspeed_SDP3X::_correct_pressure(float press)
flow_SDP3X = 0.0f; flow_SDP3X = 0.0f;
} }
// diffential pressure through pitot tube // differential pressure through pitot tube
float dp_pitot = 28557670.0f * (1.0f - 1.0f / (1.0f + (float)powf((flow_SDP3X / 5027611.0f), 1.227924f))); float dp_pitot = 28557670.0f * (1.0f - 1.0f / (1.0f + (float)powf((flow_SDP3X / 5027611.0f), 1.227924f)));
// uncorrected pressure // uncorrected pressure