ms5611: reduce macro scope

Move the addresses to .cpp where they are used. This should help
noticing discrepancies like the OSR we are using and the sampling
interval.
This commit is contained in:
Lucas De Marchi
2017-03-13 14:15:41 -07:00
committed by Lorenz Meier
parent 47d4c75214
commit 2805bffe52
2 changed files with 21 additions and 24 deletions
+19
View File
@@ -97,6 +97,25 @@ enum MS5611_BUS {
/*
* MS5611/MS5607 internal constants and data structures.
*/
#define ADDR_CMD_CONVERT_D1_OSR256 0x40 /* write to this address to start pressure conversion */
#define ADDR_CMD_CONVERT_D1_OSR512 0x42 /* write to this address to start pressure conversion */
#define ADDR_CMD_CONVERT_D1_OSR1024 0x44 /* write to this address to start pressure conversion */
#define ADDR_CMD_CONVERT_D1_OSR2048 0x46 /* write to this address to start pressure conversion */
#define ADDR_CMD_CONVERT_D1_OSR4096 0x48 /* write to this address to start pressure conversion */
#define ADDR_CMD_CONVERT_D2_OSR256 0x50 /* write to this address to start temperature conversion */
#define ADDR_CMD_CONVERT_D2_OSR512 0x52 /* write to this address to start temperature conversion */
#define ADDR_CMD_CONVERT_D2_OSR1024 0x54 /* write to this address to start temperature conversion */
#define ADDR_CMD_CONVERT_D2_OSR2048 0x56 /* write to this address to start temperature conversion */
#define ADDR_CMD_CONVERT_D2_OSR4096 0x58 /* write to this address to start temperature conversion */
/*
use an OSR of 1024 to reduce the self-heating effect of the
sensor. Information from MS tells us that some individual sensors
are quite sensitive to this effect and that reducing the OSR can
make a big difference
*/
#define ADDR_CMD_CONVERT_D1 ADDR_CMD_CONVERT_D1_OSR1024
#define ADDR_CMD_CONVERT_D2 ADDR_CMD_CONVERT_D2_OSR1024
/*
* Maximum internal conversion time for OSR 1024 is 2.28 ms. We set an update
+2 -24
View File
@@ -37,30 +37,8 @@
* Shared defines for the ms5611 driver.
*/
#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */
#define ADDR_CMD_CONVERT_D1_OSR256 0x40 /* write to this address to start pressure conversion */
#define ADDR_CMD_CONVERT_D1_OSR512 0x42 /* write to this address to start pressure conversion */
#define ADDR_CMD_CONVERT_D1_OSR1024 0x44 /* write to this address to start pressure conversion */
#define ADDR_CMD_CONVERT_D1_OSR2048 0x46 /* write to this address to start pressure conversion */
#define ADDR_CMD_CONVERT_D1_OSR4096 0x48 /* write to this address to start pressure conversion */
#define ADDR_CMD_CONVERT_D2_OSR256 0x50 /* write to this address to start temperature conversion */
#define ADDR_CMD_CONVERT_D2_OSR512 0x52 /* write to this address to start temperature conversion */
#define ADDR_CMD_CONVERT_D2_OSR1024 0x54 /* write to this address to start temperature conversion */
#define ADDR_CMD_CONVERT_D2_OSR2048 0x56 /* write to this address to start temperature conversion */
#define ADDR_CMD_CONVERT_D2_OSR4096 0x58 /* write to this address to start temperature conversion */
/*
use an OSR of 1024 to reduce the self-heating effect of the
sensor. Information from MS tells us that some individual sensors
are quite sensitive to this effect and that reducing the OSR can
make a big difference
*/
#define ADDR_CMD_CONVERT_D1 ADDR_CMD_CONVERT_D1_OSR1024
#define ADDR_CMD_CONVERT_D2 ADDR_CMD_CONVERT_D2_OSR1024
#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */
#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */
#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */
#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */
#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */
/* interface ioctls */
#define IOCTL_RESET 2