mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_Airspeed: Clean up some comments, prevent a potential out of range access
This commit is contained in:
parent
84b1a6a58b
commit
abd5bffda5
@ -83,7 +83,10 @@ public:
|
|||||||
|
|
||||||
// return true if airspeed is enabled
|
// return true if airspeed is enabled
|
||||||
bool enabled(uint8_t i) const {
|
bool enabled(uint8_t i) const {
|
||||||
return param[i].type.get() != TYPE_NONE;
|
if (i < AIRSPEED_MAX_SENSORS) {
|
||||||
|
return param[i].type.get() != TYPE_NONE;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
bool enabled(void) const { return enabled(primary); }
|
bool enabled(void) const { return enabled(primary); }
|
||||||
|
|
||||||
@ -92,8 +95,7 @@ public:
|
|||||||
state[primary].airspeed = airspeed;
|
state[primary].airspeed = airspeed;
|
||||||
}
|
}
|
||||||
|
|
||||||
// return the differential pressure in Pascal for the last
|
// return the differential pressure in Pascal for the last airspeed reading
|
||||||
// airspeed reading. Used by the calibration code
|
|
||||||
float get_differential_pressure(uint8_t i) const {
|
float get_differential_pressure(uint8_t i) const {
|
||||||
return state[i].last_pressure;
|
return state[i].last_pressure;
|
||||||
}
|
}
|
||||||
@ -215,6 +217,8 @@ private:
|
|||||||
uint8_t primary;
|
uint8_t primary;
|
||||||
|
|
||||||
void read(uint8_t i);
|
void read(uint8_t i);
|
||||||
|
// return the differential pressure in Pascal for the last airspeed reading for the requested instance
|
||||||
|
// returns 0 if the sensor is not enabled
|
||||||
float get_pressure(uint8_t i);
|
float get_pressure(uint8_t i);
|
||||||
void update_calibration(uint8_t i, float raw_pressure);
|
void update_calibration(uint8_t i, float raw_pressure);
|
||||||
void update_calibration(uint8_t i, const Vector3f &vground, int16_t max_airspeed_allowed_during_cal);
|
void update_calibration(uint8_t i, const Vector3f &vground, int16_t max_airspeed_allowed_during_cal);
|
||||||
|
Loading…
Reference in New Issue
Block a user