mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Baro: changed HIL driver to use floats and better handle starup
This commit is contained in:
parent
c995f994c5
commit
2cd781997f
@ -136,6 +136,11 @@ float AP_Baro::get_altitude(void)
|
||||
{
|
||||
float scaling, temp;
|
||||
|
||||
if (_ground_pressure == 0) {
|
||||
// called before initialisation
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (_last_altitude_t == _last_update) {
|
||||
// no new information
|
||||
return _altitude + _alt_offset;
|
||||
|
@ -3,6 +3,7 @@
|
||||
#include <AP_Baro.h>
|
||||
#include "AP_Baro_HIL.h"
|
||||
#include <AP_HAL.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
@ -21,8 +22,8 @@ uint8_t AP_Baro_HIL::read()
|
||||
if (_count != 0) {
|
||||
hal.scheduler->suspend_timer_procs();
|
||||
result = 1;
|
||||
Press = ((float)_pressure_sum) / _count;
|
||||
Temp = ((float)_temperature_sum) / _count;
|
||||
Press = _pressure_sum / _count;
|
||||
Temp = _temperature_sum / _count;
|
||||
_pressure_samples = _count;
|
||||
_count = 0;
|
||||
_pressure_sum = 0;
|
||||
|
@ -11,8 +11,8 @@ private:
|
||||
uint8_t BMP085_State;
|
||||
float Temp;
|
||||
float Press;
|
||||
int32_t _pressure_sum;
|
||||
int32_t _temperature_sum;
|
||||
float _pressure_sum;
|
||||
float _temperature_sum;
|
||||
volatile uint8_t _count;
|
||||
|
||||
public:
|
||||
|
Loading…
Reference in New Issue
Block a user