mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: Fix some typos
Fixed some typos found in the code.
This commit is contained in:
parent
28cffb9ea8
commit
9d6b015a8e
|
@ -530,7 +530,7 @@ float AP_Baro::get_external_temperature(const uint8_t instance) const
|
||||||
// The reason for not just using the baro temperature is it tends to read high,
|
// The reason for not just using the baro temperature is it tends to read high,
|
||||||
// often 30 degrees above the actual temperature. That means the
|
// often 30 degrees above the actual temperature. That means the
|
||||||
// EAS2TAS tends to be off by quite a large margin, as well as
|
// EAS2TAS tends to be off by quite a large margin, as well as
|
||||||
// the calculation of altitude difference betweeen two pressures
|
// the calculation of altitude difference between two pressures
|
||||||
// reporting a high temperature will cause the aircraft to
|
// reporting a high temperature will cause the aircraft to
|
||||||
// estimate itself as flying higher then it actually is.
|
// estimate itself as flying higher then it actually is.
|
||||||
return MIN(get_temperature(instance), INTERNAL_TEMPERATURE_CLAMP);
|
return MIN(get_temperature(instance), INTERNAL_TEMPERATURE_CLAMP);
|
||||||
|
@ -583,7 +583,7 @@ void AP_Baro::init(void)
|
||||||
{
|
{
|
||||||
init_done = true;
|
init_done = true;
|
||||||
|
|
||||||
// always set field elvation to zero on reboot in the case user
|
// always set field elevation to zero on reboot in the case user
|
||||||
// fails to update. TBD automate sanity checking error bounds on
|
// fails to update. TBD automate sanity checking error bounds on
|
||||||
// on previously saved value at new location etc.
|
// on previously saved value at new location etc.
|
||||||
if (!is_zero(_field_elevation)) {
|
if (!is_zero(_field_elevation)) {
|
||||||
|
|
|
@ -294,7 +294,7 @@ private:
|
||||||
DerivativeFilterFloat_Size7 _climb_rate_filter;
|
DerivativeFilterFloat_Size7 _climb_rate_filter;
|
||||||
AP_Float _specific_gravity; // the specific gravity of fluid for an ROV 1.00 for freshwater, 1.024 for salt water
|
AP_Float _specific_gravity; // the specific gravity of fluid for an ROV 1.00 for freshwater, 1.024 for salt water
|
||||||
AP_Float _user_ground_temperature; // user override of the ground temperature used for EAS2TAS
|
AP_Float _user_ground_temperature; // user override of the ground temperature used for EAS2TAS
|
||||||
float _guessed_ground_temperature; // currently ground temperature estimate using our best abailable source
|
float _guessed_ground_temperature; // currently ground temperature estimate using our best available source
|
||||||
|
|
||||||
// when did we last notify the GCS of new pressure reference?
|
// when did we last notify the GCS of new pressure reference?
|
||||||
uint32_t _last_notify_ms;
|
uint32_t _last_notify_ms;
|
||||||
|
|
|
@ -70,7 +70,7 @@ bool AP_Baro_BMP085::_init()
|
||||||
// get pointer to i2c bus semaphore
|
// get pointer to i2c bus semaphore
|
||||||
AP_HAL::Semaphore *sem = _dev->get_semaphore();
|
AP_HAL::Semaphore *sem = _dev->get_semaphore();
|
||||||
|
|
||||||
// take i2c bus sempahore
|
// take i2c bus semaphore
|
||||||
WITH_SEMAPHORE(sem);
|
WITH_SEMAPHORE(sem);
|
||||||
|
|
||||||
if (BMP085_EOC >= 0) {
|
if (BMP085_EOC >= 0) {
|
||||||
|
@ -177,7 +177,7 @@ bool AP_Baro_BMP085::_read_prom(uint16_t *prom)
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
This is a state machine. Acumulate a new sensor reading.
|
This is a state machine. Accumulate a new sensor reading.
|
||||||
*/
|
*/
|
||||||
void AP_Baro_BMP085::_timer(void)
|
void AP_Baro_BMP085::_timer(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -127,7 +127,7 @@ bool AP_Baro_BMP280::_init()
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// acumulate a new sensor reading
|
// accumulate a new sensor reading
|
||||||
void AP_Baro_BMP280::_timer(void)
|
void AP_Baro_BMP280::_timer(void)
|
||||||
{
|
{
|
||||||
uint8_t buf[6];
|
uint8_t buf[6];
|
||||||
|
|
|
@ -130,7 +130,7 @@ bool AP_Baro_BMP388::init()
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// acumulate a new sensor reading
|
// accumulate a new sensor reading
|
||||||
void AP_Baro_BMP388::timer(void)
|
void AP_Baro_BMP388::timer(void)
|
||||||
{
|
{
|
||||||
uint8_t buf[7];
|
uint8_t buf[7];
|
||||||
|
|
|
@ -67,7 +67,7 @@ void AP_Baro_Backend::_copy_to_frontend(uint8_t instance, float pressure, float
|
||||||
static constexpr float FILTER_KOEF = 0.1f;
|
static constexpr float FILTER_KOEF = 0.1f;
|
||||||
|
|
||||||
/* Check that the baro value is valid by using a mean filter. If the
|
/* Check that the baro value is valid by using a mean filter. If the
|
||||||
* value is further than filtrer_range from mean value, it is
|
* value is further than filter_range from mean value, it is
|
||||||
* rejected.
|
* rejected.
|
||||||
*/
|
*/
|
||||||
bool AP_Baro_Backend::pressure_ok(float press)
|
bool AP_Baro_Backend::pressure_ok(float press)
|
||||||
|
|
|
@ -20,7 +20,7 @@ public:
|
||||||
void backend_update(uint8_t instance);
|
void backend_update(uint8_t instance);
|
||||||
|
|
||||||
// Check that the baro valid by using a mean filter.
|
// Check that the baro valid by using a mean filter.
|
||||||
// If the value further that filtrer_range from mean value, it is rejected.
|
// If the value further that filter_range from mean value, it is rejected.
|
||||||
bool pressure_ok(float press);
|
bool pressure_ok(float press);
|
||||||
uint32_t get_error_count() const { return _error_count; }
|
uint32_t get_error_count() const { return _error_count; }
|
||||||
|
|
||||||
|
|
|
@ -246,7 +246,7 @@ void AP_Baro_DPS280::check_health(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// acumulate a new sensor reading
|
// accumulate a new sensor reading
|
||||||
void AP_Baro_DPS280::timer(void)
|
void AP_Baro_DPS280::timer(void)
|
||||||
{
|
{
|
||||||
uint8_t buf[6];
|
uint8_t buf[6];
|
||||||
|
|
|
@ -88,7 +88,7 @@ AP_Baro_DroneCAN* AP_Baro_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_droneca
|
||||||
|
|
||||||
if (create_new) {
|
if (create_new) {
|
||||||
bool already_detected = false;
|
bool already_detected = false;
|
||||||
//Check if there's an empty spot for possible registeration
|
//Check if there's an empty spot for possible registration
|
||||||
for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {
|
for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {
|
||||||
if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) {
|
if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) {
|
||||||
//Already Detected
|
//Already Detected
|
||||||
|
|
|
@ -179,7 +179,7 @@ void AP_Baro_FBM320::calculate_PT(int32_t UT, int32_t UP, int32_t &pressure, int
|
||||||
pressure = ((X31 + X32) >> 15) + PP4 + 99880;
|
pressure = ((X31 + X32) >> 15) + PP4 + 99880;
|
||||||
}
|
}
|
||||||
|
|
||||||
// acumulate a new sensor reading
|
// accumulate a new sensor reading
|
||||||
void AP_Baro_FBM320::timer(void)
|
void AP_Baro_FBM320::timer(void)
|
||||||
{
|
{
|
||||||
uint8_t buf[3];
|
uint8_t buf[3];
|
||||||
|
|
|
@ -212,7 +212,7 @@ bool AP_Baro_LPS2XH::_check_whoami(void)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// acumulate a new sensor reading
|
// accumulate a new sensor reading
|
||||||
void AP_Baro_LPS2XH::_timer(void)
|
void AP_Baro_LPS2XH::_timer(void)
|
||||||
{
|
{
|
||||||
uint8_t status;
|
uint8_t status;
|
||||||
|
|
|
@ -179,7 +179,7 @@ int32_t AP_Baro_SPL06::raw_value_scale_factor(uint8_t oversampling)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// acumulate a new sensor reading
|
// accumulate a new sensor reading
|
||||||
void AP_Baro_SPL06::_timer(void)
|
void AP_Baro_SPL06::_timer(void)
|
||||||
{
|
{
|
||||||
uint8_t buf[3];
|
uint8_t buf[3];
|
||||||
|
|
Loading…
Reference in New Issue