mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
uncrustify libraries/AP_Baro/AP_Baro_MS5611.h
This commit is contained in:
parent
dbb7b33728
commit
963e250dca
@ -7,48 +7,49 @@
|
||||
|
||||
class AP_Baro_MS5611 : public AP_Baro
|
||||
{
|
||||
public:
|
||||
AP_Baro_MS5611() {} // Constructor
|
||||
public:
|
||||
AP_Baro_MS5611() {
|
||||
} // Constructor
|
||||
|
||||
/* AP_Baro public interface: */
|
||||
bool init(AP_PeriodicProcess *scheduler);
|
||||
uint8_t read();
|
||||
float get_pressure(); // in mbar*100 units
|
||||
float get_temperature(); // in celsius degrees * 100 units
|
||||
/* AP_Baro public interface: */
|
||||
bool init(AP_PeriodicProcess *scheduler);
|
||||
uint8_t read();
|
||||
float get_pressure(); // in mbar*100 units
|
||||
float get_temperature(); // in celsius degrees * 100 units
|
||||
|
||||
int32_t get_raw_pressure();
|
||||
int32_t get_raw_temp();
|
||||
int32_t get_raw_pressure();
|
||||
int32_t get_raw_temp();
|
||||
|
||||
void _calculate();
|
||||
void _calculate();
|
||||
|
||||
private:
|
||||
/* Asynchronous handler functions: */
|
||||
static void _update(uint32_t );
|
||||
/* Asynchronous state: */
|
||||
static volatile bool _updated;
|
||||
static volatile uint8_t _d1_count;
|
||||
static volatile uint8_t _d2_count;
|
||||
static volatile uint32_t _s_D1, _s_D2;
|
||||
static uint8_t _state;
|
||||
static uint32_t _timer;
|
||||
/* Gates access to asynchronous state: */
|
||||
static bool _sync_access;
|
||||
private:
|
||||
/* Asynchronous handler functions: */
|
||||
static void _update(uint32_t );
|
||||
/* Asynchronous state: */
|
||||
static volatile bool _updated;
|
||||
static volatile uint8_t _d1_count;
|
||||
static volatile uint8_t _d2_count;
|
||||
static volatile uint32_t _s_D1, _s_D2;
|
||||
static uint8_t _state;
|
||||
static uint32_t _timer;
|
||||
/* Gates access to asynchronous state: */
|
||||
static bool _sync_access;
|
||||
|
||||
/* Serial wrapper functions: */
|
||||
static uint8_t _spi_read(uint8_t reg);
|
||||
static uint16_t _spi_read_16bits(uint8_t reg);
|
||||
static uint32_t _spi_read_adc();
|
||||
static void _spi_write(uint8_t reg);
|
||||
/* Serial wrapper functions: */
|
||||
static uint8_t _spi_read(uint8_t reg);
|
||||
static uint16_t _spi_read_16bits(uint8_t reg);
|
||||
static uint32_t _spi_read_adc();
|
||||
static void _spi_write(uint8_t reg);
|
||||
|
||||
|
||||
float Temp;
|
||||
float Press;
|
||||
float Temp;
|
||||
float Press;
|
||||
|
||||
int32_t _raw_press;
|
||||
int32_t _raw_temp;
|
||||
// Internal calibration registers
|
||||
uint16_t C1,C2,C3,C4,C5,C6;
|
||||
float D1,D2;
|
||||
int32_t _raw_press;
|
||||
int32_t _raw_temp;
|
||||
// Internal calibration registers
|
||||
uint16_t C1,C2,C3,C4,C5,C6;
|
||||
float D1,D2;
|
||||
};
|
||||
|
||||
#endif // __AP_BARO_MS5611_H__
|
||||
|
Loading…
Reference in New Issue
Block a user