mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Baro_MS5611.h: reorganized
* moved ms5611 macros to c file * reorganized class declaration & retabbed * made Temp, Pres, and Alt private variables.
This commit is contained in:
parent
34cebd8a3e
commit
c407b0d85e
@ -35,6 +35,22 @@
|
||||
#include <SPI.h>
|
||||
#include "APM_MS5611.h"
|
||||
|
||||
|
||||
#define MS5611_CS A2 // Chip select pin (provisional)
|
||||
|
||||
#define CMD_MS5611_RESET 0x1E
|
||||
#define CMD_MS5611_PROM_Setup 0xA0
|
||||
#define CMD_MS5611_PROM_C1 0xA2
|
||||
#define CMD_MS5611_PROM_C2 0xA4
|
||||
#define CMD_MS5611_PROM_C3 0xA6
|
||||
#define CMD_MS5611_PROM_C4 0xA8
|
||||
#define CMD_MS5611_PROM_C5 0xAA
|
||||
#define CMD_MS5611_PROM_C6 0xAC
|
||||
#define CMD_MS5611_PROM_CRC 0xAE
|
||||
#define CMD_CONVERT_D1_OSR4096 0x48 // Maximun resolution
|
||||
#define CMD_CONVERT_D2_OSR4096 0x58 // Maximun resolution
|
||||
|
||||
|
||||
uint8_t MS5611_SPI_read(byte reg)
|
||||
{
|
||||
byte dump;
|
||||
|
@ -1,46 +1,33 @@
|
||||
#ifndef APM_MS5611_h
|
||||
#define APM_MS5611_h
|
||||
|
||||
#define MS5611_CS A2 // Chip select pin (provisional)
|
||||
|
||||
#define CMD_MS5611_RESET 0x1E
|
||||
#define CMD_MS5611_PROM_Setup 0xA0
|
||||
#define CMD_MS5611_PROM_C1 0xA2
|
||||
#define CMD_MS5611_PROM_C2 0xA4
|
||||
#define CMD_MS5611_PROM_C3 0xA6
|
||||
#define CMD_MS5611_PROM_C4 0xA8
|
||||
#define CMD_MS5611_PROM_C5 0xAA
|
||||
#define CMD_MS5611_PROM_C6 0xAC
|
||||
#define CMD_MS5611_PROM_CRC 0xAE
|
||||
#define CMD_CONVERT_D1_OSR4096 0x48 // Maximun resolution
|
||||
#define CMD_CONVERT_D2_OSR4096 0x58 // Maximun resolution
|
||||
#ifndef __AP_BARO_MS5611_H__
|
||||
#define __AP_BARO_MS5611_H__
|
||||
|
||||
|
||||
class APM_MS5611_Class
|
||||
class AP_Baro_MS5611
|
||||
{
|
||||
private:
|
||||
// Internal calibration registers
|
||||
uint16_t C1,C2,C3,C4,C5,C6;
|
||||
uint32_t D1,D2;
|
||||
void calculate();
|
||||
uint8_t MS5611_Ready();
|
||||
long MS5611_timer;
|
||||
uint8_t MS5611_State;
|
||||
|
||||
public:
|
||||
//uint16_t C1,C2,C3,C4,C5,C6;
|
||||
//uint32_t D1,D2;
|
||||
int16_t Temp;
|
||||
int32_t Press;
|
||||
int32_t Alt;
|
||||
AP_Baro_MS5611() {} // Constructor
|
||||
|
||||
|
||||
APM_MS5611_Class(); // Constructor
|
||||
void init();
|
||||
uint8_t read();
|
||||
uint32_t get_pressure(); // in mbar*100 units
|
||||
uint16_t get_temperature(); // in celsius degrees * 100 units
|
||||
float get_altitude(); // in meter units
|
||||
void init();
|
||||
uint8_t read();
|
||||
uint32_t get_pressure(); // in mbar*100 units
|
||||
uint16_t get_temperature(); // in celsius degrees * 100 units
|
||||
float get_altitude(); // in meter units
|
||||
|
||||
private:
|
||||
|
||||
int16_t Temp;
|
||||
int32_t Press;
|
||||
int32_t Alt;
|
||||
|
||||
// Internal calibration registers
|
||||
uint16_t C1,C2,C3,C4,C5,C6;
|
||||
uint32_t D1,D2;
|
||||
void calculate();
|
||||
uint8_t MS5611_Ready();
|
||||
long MS5611_timer;
|
||||
uint8_t MS5611_State;
|
||||
};
|
||||
|
||||
#endif
|
||||
#endif // __AP_BARO_MS5611_H__
|
||||
|
Loading…
Reference in New Issue
Block a user