mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 09:33:59 -03:00
AP_Baro_MS5611: conform to AP_Baro interface
This commit is contained in:
parent
d113992c10
commit
a41b6da263
@ -2,25 +2,31 @@
|
|||||||
#ifndef __AP_BARO_MS5611_H__
|
#ifndef __AP_BARO_MS5611_H__
|
||||||
#define __AP_BARO_MS5611_H__
|
#define __AP_BARO_MS5611_H__
|
||||||
|
|
||||||
|
#include "AP_Baro.h"
|
||||||
|
|
||||||
class AP_Baro_MS5611
|
class AP_Baro_MS5611 : public AP_Baro
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
AP_Baro_MS5611() {} // Constructor
|
AP_Baro_MS5611() {} // Constructor
|
||||||
|
|
||||||
|
|
||||||
void init();
|
void init();
|
||||||
|
|
||||||
|
/* AP_Baro public interface: */
|
||||||
uint8_t read();
|
uint8_t read();
|
||||||
uint32_t get_pressure(); // in mbar*100 units
|
int32_t get_pressure(); // in mbar*100 units
|
||||||
uint16_t get_temperature(); // in celsius degrees * 100 units
|
int16_t get_temperature(); // in celsius degrees * 100 units
|
||||||
float get_altitude(); // in meter units
|
float get_altitude(); // in meter units
|
||||||
|
|
||||||
|
int32_t get_raw_pressure();
|
||||||
|
int32_t get_raw_temp();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
int16_t Temp;
|
int16_t Temp;
|
||||||
int32_t Press;
|
int32_t Press;
|
||||||
int32_t Alt;
|
int32_t Alt;
|
||||||
|
|
||||||
|
int32_t _raw_press;
|
||||||
|
int32_t _raw_temp;
|
||||||
// Internal calibration registers
|
// Internal calibration registers
|
||||||
uint16_t C1,C2,C3,C4,C5,C6;
|
uint16_t C1,C2,C3,C4,C5,C6;
|
||||||
uint32_t D1,D2;
|
uint32_t D1,D2;
|
||||||
|
Loading…
Reference in New Issue
Block a user