mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: params always use set method
This commit is contained in:
parent
2f7f187e18
commit
4fa0bcaa91
|
@ -885,7 +885,7 @@ void AP_Baro::update(void)
|
|||
// update altitude calculation
|
||||
float ground_pressure = sensors[i].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 corrected_pressure = sensors[i].pressure + sensors[i].p_correction;
|
||||
|
|
|
@ -173,7 +173,7 @@ public:
|
|||
uint8_t num_instances(void) const { return _num_sensors; }
|
||||
|
||||
// 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
|
||||
float get_baro_drift_offset(void) const { return _alt_offset_active; }
|
||||
|
|
Loading…
Reference in New Issue