Browse Source

AP_Baro: params always use set method

apm_2208
Iampete1 3 years ago committed by Peter Hall
parent
commit
4fa0bcaa91
  1. 2
      libraries/AP_Baro/AP_Baro.cpp
  2. 2
      libraries/AP_Baro/AP_Baro.h

2
libraries/AP_Baro/AP_Baro.cpp

@ -885,7 +885,7 @@ void AP_Baro::update(void)
// update altitude calculation // update altitude calculation
float ground_pressure = sensors[i].ground_pressure; float ground_pressure = sensors[i].ground_pressure;
if (!is_positive(ground_pressure) || isnan(ground_pressure) || isinf(ground_pressure)) { if (!is_positive(ground_pressure) || isnan(ground_pressure) || isinf(ground_pressure)) {
sensors[i].ground_pressure = sensors[i].pressure; sensors[i].ground_pressure.set(sensors[i].pressure);
} }
float altitude = sensors[i].altitude; float altitude = sensors[i].altitude;
float corrected_pressure = sensors[i].pressure + sensors[i].p_correction; float corrected_pressure = sensors[i].pressure + sensors[i].p_correction;

2
libraries/AP_Baro/AP_Baro.h

@ -173,7 +173,7 @@ public:
uint8_t num_instances(void) const { return _num_sensors; } uint8_t num_instances(void) const { return _num_sensors; }
// set baro drift amount // set baro drift amount
void set_baro_drift_altitude(float alt) { _alt_offset = alt; } void set_baro_drift_altitude(float alt) { _alt_offset.set(alt); }
// get baro drift amount // get baro drift amount
float get_baro_drift_offset(void) const { return _alt_offset_active; } float get_baro_drift_offset(void) const { return _alt_offset_active; }

Loading…
Cancel
Save