forked from Archive/PX4-Autopilot
ms5611: reduced OSR to 1024
this reduces self-heating of the sensor which reduces the amount of altitude change when warming up. Apparently some individual sensors are severely affected by this. Unfortunately it raises the noise level, but Paul is confident it won't be a significant issue
This commit is contained in:
parent
73f48b78aa
commit
efd4552e37
|
@ -38,8 +38,26 @@
|
|||
*/
|
||||
|
||||
#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */
|
||||
#define ADDR_CMD_CONVERT_D1 0x48 /* write to this address to start pressure conversion */
|
||||
#define ADDR_CMD_CONVERT_D2 0x58 /* write to this address to start temperature conversion */
|
||||
#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 */
|
||||
|
|
Loading…
Reference in New Issue