5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-12 02:48:28 -04:00

uncrustify libraries/AP_Baro/AP_Baro_BMP085.h

This commit is contained in:
uncrustify 2012-08-16 23:09:24 -07:00 committed by Pat Hickey
parent 5a99d6b697
commit cfcef93e16

View File

@ -9,45 +9,45 @@
class AP_Baro_BMP085 : public AP_Baro class AP_Baro_BMP085 : public AP_Baro
{ {
public: public:
AP_Baro_BMP085(bool apm2_hardware): AP_Baro_BMP085(bool apm2_hardware) :
_apm2_hardware(apm2_hardware) { _apm2_hardware(apm2_hardware) {
_pressure_samples = 1; _pressure_samples = 1;
}; // Constructor }; // Constructor
/* AP_Baro public interface: */ /* AP_Baro public interface: */
bool init(AP_PeriodicProcess * scheduler); bool init(AP_PeriodicProcess * scheduler);
uint8_t read(); uint8_t read();
float get_pressure(); float get_pressure();
float get_temperature(); float get_temperature();
int32_t get_raw_pressure(); int32_t get_raw_pressure();
int32_t get_raw_temp(); int32_t get_raw_temp();
private: private:
int32_t RawPress; int32_t RawPress;
int32_t RawTemp; int32_t RawTemp;
int16_t Temp; int16_t Temp;
uint32_t Press; uint32_t Press;
bool _apm2_hardware; bool _apm2_hardware;
// State machine // State machine
uint8_t BMP085_State; uint8_t BMP085_State;
// Internal calibration registers // Internal calibration registers
int16_t ac1, ac2, ac3, b1, b2, mb, mc, md; int16_t ac1, ac2, ac3, b1, b2, mb, mc, md;
uint16_t ac4, ac5, ac6; uint16_t ac4, ac5, ac6;
AverageFilterInt32_Size4 _temp_filter; AverageFilterInt32_Size4 _temp_filter;
uint32_t _retry_time; uint32_t _retry_time;
void Command_ReadPress(); void Command_ReadPress();
void Command_ReadTemp(); void Command_ReadTemp();
void ReadPress(); void ReadPress();
void ReadTemp(); void ReadTemp();
void Calculate(); void Calculate();
}; };
#endif // __AP_BARO_BMP085_H__ #endif // __AP_BARO_BMP085_H__