Header file for all #define constants and function prototypes. More...
Go to the source code of this file.
Classes | |
struct | bmp085_smd500_calibration_param_t |
struct | bmp085_t |
Defines | |
#define | BMP085_ADC_OUT_LSB_REG 0xF7 |
#define | BMP085_ADC_OUT_MSB_REG 0xF6 |
#define | BMP085_AL_VERSION__LEN 4 |
#define | BMP085_AL_VERSION__MSK 0xF0 |
#define | BMP085_AL_VERSION__POS 4 |
#define | BMP085_AL_VERSION__REG BMP085_VERSION_REG |
#define | BMP085_BUS_RD_PARAM_ORDER device_addr, register_addr, register_data, read_length |
#define | BMP085_BUS_RD_PARAM_TYPES unsigned char, unsigned char, unsigned char*, unsigned char |
#define | BMP085_BUS_RD_RETURN_TYPE char |
#define | BMP085_BUS_READ_FUNC(device_addr, register_addr, register_data, read_length) bus_read( device_addr, register_addr, register_data, read_length ) |
#define | BMP085_BUS_WR_PARAM_ORDER device_addr, register_addr, register_data, write_length |
#define | BMP085_BUS_WR_PARAM_TYPES unsigned char, unsigned char, unsigned char*, unsigned char |
#define | BMP085_BUS_WR_RETURN_TYPE char |
#define | BMP085_BUS_WRITE_FUNC(device_addr, register_addr, register_data, write_length) bus_write( device_addr, register_addr, register_data, write_length ) |
#define | bmp085_calc_pressure(up) bmp085_get_pressure(up) |
#define | bmp085_calc_temperature(ut) bmp085_get_temperature(ut) |
#define | BMP085_CHIP_ID 0x55 |
#define | BMP085_CHIP_ID__LEN 8 |
#define | BMP085_CHIP_ID__MSK 0xFF |
#define | BMP085_CHIP_ID__POS 0 |
#define | BMP085_CHIP_ID__REG BMP085_CHIP_ID_REG |
#define | BMP085_CHIP_ID_REG 0xD0 |
#define | BMP085_CTRL_MEAS_REG 0xF4 |
#define | BMP085_GET_BITSLICE(regvar, bitname) (regvar & bitname##__MSK) >> bitname##__POS |
#define | BMP085_I2C_ADDR (0xEE >> 1) |
#define | BMP085_MDELAY_DATA_TYPE unsigned int |
#define | BMP085_MDELAY_RETURN_TYPE void |
#define | BMP085_ML_VERSION__LEN 4 |
#define | BMP085_ML_VERSION__MSK 0x0F |
#define | BMP085_ML_VERSION__POS 0 |
#define | BMP085_ML_VERSION__REG BMP085_VERSION_REG |
#define | BMP085_P_MEASURE 0x34 |
#define | BMP085_PROM_DATA__LEN 22 |
#define | BMP085_PROM_START__ADDR 0xAA |
#define | bmp085_read_cal_param() bmp085_get_cal_param() |
#define | bmp085_read_reg(address, data, length) bmp085_get_reg(address, data, length) |
#define | bmp085_read_up() bmp085_get_up() |
#define | bmp085_read_ut() bmp085_get_ut() |
#define | BMP085_SET_BITSLICE(regvar, bitname, val) (regvar & ~bitname##__MSK) | ((val<<bitname##__POS)&bitname##__MSK) |
#define | BMP085_SOFT_RESET_REG 0xE0 |
#define | BMP085_T_MEASURE 0x2E |
#define | BMP085_TEMP_CONVERSION_TIME 5 |
#define | BMP085_VERSION_REG 0xD1 |
#define | bmp085_write_reg(address, data, length) bmp085_set_reg(address, data, length) |
#define | BOSCH_PRESSURE_BMP085 85 |
#define | BOSCH_PRESSURE_SMD500 05 |
#define | E_BMP_COMM_RES (char)-1 |
#define | E_BMP_NULL_PTR (char)-127 |
#define | E_BMP_OUT_OF_RANGE (char)-2 |
#define | E_SENSOR_NOT_DETECTED (char) 0 |
#define | SMD500_MASTERCLOCK_1MHZ 0 |
#define | SMD500_MASTERCLOCK_32768HZ 0x04 |
#define | SMD500_P_MEASURE 0xF0 |
#define | SMD500_PARAM_M1 -2218 |
#define | SMD500_PARAM_M2 -457 |
#define | SMD500_PARAM_M3 -1984 |
#define | SMD500_PARAM_M4 8808 |
#define | SMD500_PARAM_M5 496 |
#define | SMD500_PARAM_M6 1415 |
#define | SMD500_PARAM_MB -4955 |
#define | SMD500_PARAM_MC 11611 |
#define | SMD500_PARAM_MD -12166 |
#define | SMD500_PARAM_ME -17268 |
#define | SMD500_PARAM_MF -8970 |
#define | SMD500_PARAM_MG 3038 |
#define | SMD500_PARAM_MH -7357 |
#define | SMD500_PARAM_MI 3791 |
#define | SMD500_PARAM_MJ 64385 |
#define | SMD500_PROM_DATA__LEN 8 |
#define | SMD500_PROM_START__ADDR 0xF8 |
#define | smd500_read_cal_param() smd500_get_cal_param() |
#define | SMD500_STANDBY 0 |
#define | SMD500_T_MEASURE 0x6A |
#define | SMD500_T_RESOLUTION_13BIT 0 |
#define | SMD500_T_RESOLUTION_16BIT 0x80 |
#define | SMD500_TEMP_CONVERSION_TIME_13 9 |
#define | SMD500_TEMP_CONVERSION_TIME_16 34 |
Functions | |
int | bmp085_get_cal_param (void) |
long | bmp085_get_pressure (unsigned long up) |
char | bmp085_get_reg (unsigned char, unsigned char *, unsigned char) |
short | bmp085_get_temperature (unsigned long ut) |
unsigned long | bmp085_get_up (void) |
unsigned short | bmp085_get_ut (void) |
int | bmp085_init (bmp085_t *) |
char | bmp085_set_reg (unsigned char, unsigned char *, unsigned char) |
int | smd500_get_cal_param (void) |
Header file for all #define constants and function prototypes.
Definition in file bmp085_bst.h.
#define BMP085_ADC_OUT_LSB_REG 0xF7 |
Definition at line 189 of file bmp085_bst.h.
#define BMP085_ADC_OUT_MSB_REG 0xF6 |
Definition at line 188 of file bmp085_bst.h.
#define BMP085_AL_VERSION__LEN 4 |
Definition at line 299 of file bmp085_bst.h.
#define BMP085_AL_VERSION__MSK 0xF0 |
Definition at line 300 of file bmp085_bst.h.
#define BMP085_AL_VERSION__POS 4 |
Definition at line 298 of file bmp085_bst.h.
Definition at line 301 of file bmp085_bst.h.
#define BMP085_BUS_RD_PARAM_ORDER device_addr, register_addr, register_data, read_length |
links the order of parameters defined in BMP085_BUS_RD_PARAM_TYPE to function calls used inside the API
Definition at line 145 of file bmp085_bst.h.
#define BMP085_BUS_RD_PARAM_TYPES unsigned char, unsigned char, unsigned char*, unsigned char |
defines the calling parameter types of the BMP085_RD_FUNCTION
Definition at line 140 of file bmp085_bst.h.
#define BMP085_BUS_RD_RETURN_TYPE char |
defines the return parameter type of the BMP085_RD_FUNCTION
Definition at line 135 of file bmp085_bst.h.
#define BMP085_BUS_READ_FUNC | ( | device_addr, | |
register_addr, | |||
register_data, | |||
read_length | |||
) | bus_read( device_addr, register_addr, register_data, read_length ) |
Definition at line 149 of file bmp085_bst.h.
#define BMP085_BUS_WR_PARAM_ORDER device_addr, register_addr, register_data, write_length |
links the order of parameters defined in BMP085_BUS_WR_PARAM_TYPE to function calls used inside the API
Definition at line 124 of file bmp085_bst.h.
#define BMP085_BUS_WR_PARAM_TYPES unsigned char, unsigned char, unsigned char*, unsigned char |
defines the calling parameter types of the BMP085_WR_FUNCTION
Definition at line 119 of file bmp085_bst.h.
#define BMP085_BUS_WR_RETURN_TYPE char |
define for used read and write macros defines the return parameter type of the BMP085_WR_FUNCTION
Definition at line 114 of file bmp085_bst.h.
#define BMP085_BUS_WRITE_FUNC | ( | device_addr, | |
register_addr, | |||
register_data, | |||
write_length | |||
) | bus_write( device_addr, register_addr, register_data, write_length ) |
Definition at line 128 of file bmp085_bst.h.
#define bmp085_calc_pressure | ( | up | ) | bmp085_get_pressure(up) |
Definition at line 90 of file bmp085_bst.h.
#define bmp085_calc_temperature | ( | ut | ) | bmp085_get_temperature(ut) |
Definition at line 88 of file bmp085_bst.h.
#define BMP085_CHIP_ID 0x55 |
Definition at line 157 of file bmp085_bst.h.
#define BMP085_CHIP_ID__LEN 8 |
Definition at line 287 of file bmp085_bst.h.
#define BMP085_CHIP_ID__MSK 0xFF |
Definition at line 286 of file bmp085_bst.h.
#define BMP085_CHIP_ID__POS 0 |
Definition at line 285 of file bmp085_bst.h.
Definition at line 288 of file bmp085_bst.h.
#define BMP085_CHIP_ID_REG 0xD0 |
Definition at line 184 of file bmp085_bst.h.
#define BMP085_CTRL_MEAS_REG 0xF4 |
Definition at line 187 of file bmp085_bst.h.
#define BMP085_GET_BITSLICE | ( | regvar, | |
bitname | |||
) | (regvar & bitname##__MSK) >> bitname##__POS |
Definition at line 313 of file bmp085_bst.h.
#define BMP085_I2C_ADDR (0xEE >> 1) |
Definition at line 165 of file bmp085_bst.h.
#define BMP085_MDELAY_DATA_TYPE unsigned int |
Definition at line 235 of file bmp085_bst.h.
#define BMP085_MDELAY_RETURN_TYPE void |
Definition at line 236 of file bmp085_bst.h.
#define BMP085_ML_VERSION__LEN 4 |
Definition at line 292 of file bmp085_bst.h.
#define BMP085_ML_VERSION__MSK 0x0F |
Definition at line 293 of file bmp085_bst.h.
#define BMP085_ML_VERSION__POS 0 |
Definition at line 291 of file bmp085_bst.h.
Definition at line 294 of file bmp085_bst.h.
#define BMP085_P_MEASURE 0x34 |
Definition at line 194 of file bmp085_bst.h.
#define BMP085_PROM_DATA__LEN 22 |
Definition at line 182 of file bmp085_bst.h.
#define BMP085_PROM_START__ADDR 0xAA |
Definition at line 181 of file bmp085_bst.h.
#define bmp085_read_cal_param | ( | ) | bmp085_get_cal_param() |
Definition at line 100 of file bmp085_bst.h.
#define bmp085_read_reg | ( | address, | |
data, | |||
length | |||
) | bmp085_get_reg(address, data, length) |
Definition at line 96 of file bmp085_bst.h.
#define bmp085_read_up | ( | ) | bmp085_get_up() |
Definition at line 94 of file bmp085_bst.h.
#define bmp085_read_ut | ( | ) | bmp085_get_ut() |
Definition at line 92 of file bmp085_bst.h.
#define BMP085_SET_BITSLICE | ( | regvar, | |
bitname, | |||
val | |||
) | (regvar & ~bitname##__MSK) | ((val<<bitname##__POS)&bitname##__MSK) |
Definition at line 316 of file bmp085_bst.h.
#define BMP085_SOFT_RESET_REG 0xE0 |
Definition at line 191 of file bmp085_bst.h.
#define BMP085_T_MEASURE 0x2E |
Definition at line 193 of file bmp085_bst.h.
#define BMP085_TEMP_CONVERSION_TIME 5 |
Definition at line 196 of file bmp085_bst.h.
#define BMP085_VERSION_REG 0xD1 |
Definition at line 185 of file bmp085_bst.h.
#define bmp085_write_reg | ( | address, | |
data, | |||
length | |||
) | bmp085_set_reg(address, data, length) |
Definition at line 98 of file bmp085_bst.h.
#define BOSCH_PRESSURE_BMP085 85 |
Definition at line 159 of file bmp085_bst.h.
#define BOSCH_PRESSURE_SMD500 05 |
Definition at line 158 of file bmp085_bst.h.
#define E_BMP_COMM_RES (char)-1 |
Definition at line 172 of file bmp085_bst.h.
#define E_BMP_NULL_PTR (char)-127 |
Definition at line 171 of file bmp085_bst.h.
#define E_BMP_OUT_OF_RANGE (char)-2 |
Definition at line 173 of file bmp085_bst.h.
#define E_SENSOR_NOT_DETECTED (char) 0 |
Definition at line 174 of file bmp085_bst.h.
#define SMD500_MASTERCLOCK_1MHZ 0 |
Definition at line 223 of file bmp085_bst.h.
#define SMD500_MASTERCLOCK_32768HZ 0x04 |
Definition at line 222 of file bmp085_bst.h.
#define SMD500_P_MEASURE 0xF0 |
Definition at line 227 of file bmp085_bst.h.
#define SMD500_PARAM_M1 -2218 |
Definition at line 203 of file bmp085_bst.h.
#define SMD500_PARAM_M2 -457 |
Definition at line 204 of file bmp085_bst.h.
#define SMD500_PARAM_M3 -1984 |
Definition at line 205 of file bmp085_bst.h.
#define SMD500_PARAM_M4 8808 |
Definition at line 206 of file bmp085_bst.h.
#define SMD500_PARAM_M5 496 |
Definition at line 207 of file bmp085_bst.h.
#define SMD500_PARAM_M6 1415 |
Definition at line 208 of file bmp085_bst.h.
#define SMD500_PARAM_MB -4955 |
Definition at line 210 of file bmp085_bst.h.
#define SMD500_PARAM_MC 11611 |
Definition at line 211 of file bmp085_bst.h.
#define SMD500_PARAM_MD -12166 |
Definition at line 212 of file bmp085_bst.h.
#define SMD500_PARAM_ME -17268 |
Definition at line 213 of file bmp085_bst.h.
#define SMD500_PARAM_MF -8970 |
Definition at line 214 of file bmp085_bst.h.
#define SMD500_PARAM_MG 3038 |
Definition at line 216 of file bmp085_bst.h.
#define SMD500_PARAM_MH -7357 |
Definition at line 217 of file bmp085_bst.h.
#define SMD500_PARAM_MI 3791 |
Definition at line 218 of file bmp085_bst.h.
#define SMD500_PARAM_MJ 64385 |
Definition at line 219 of file bmp085_bst.h.
#define SMD500_PROM_DATA__LEN 8 |
Definition at line 201 of file bmp085_bst.h.
#define SMD500_PROM_START__ADDR 0xF8 |
Definition at line 200 of file bmp085_bst.h.
#define smd500_read_cal_param | ( | ) | smd500_get_cal_param() |
Definition at line 102 of file bmp085_bst.h.
#define SMD500_STANDBY 0 |
Definition at line 221 of file bmp085_bst.h.
#define SMD500_T_MEASURE 0x6A |
Definition at line 226 of file bmp085_bst.h.
#define SMD500_T_RESOLUTION_13BIT 0 |
Definition at line 224 of file bmp085_bst.h.
#define SMD500_T_RESOLUTION_16BIT 0x80 |
Definition at line 225 of file bmp085_bst.h.
#define SMD500_TEMP_CONVERSION_TIME_13 9 |
Definition at line 229 of file bmp085_bst.h.
#define SMD500_TEMP_CONVERSION_TIME_16 34 |
Definition at line 230 of file bmp085_bst.h.
int bmp085_get_cal_param | ( | void | ) |
read out parameters cal_param from BMP085 memory
Definition at line 178 of file bmp085_bst.c.
long bmp085_get_pressure | ( | unsigned long | up | ) |
calculate pressure from up up was read from the device via I2C and fed into the right calc path for either SMD500 or BMP085 In case of SMD500 value averaging is done in this function, in case of BMP085 averaging is done through oversampling by the sensor IC
ut | parameter ut read from device |
Definition at line 279 of file bmp085_bst.c.
char bmp085_get_reg | ( | unsigned | char, |
unsigned char * | , | ||
unsigned | char | ||
) |
short bmp085_get_temperature | ( | unsigned long | ut | ) |
calculate temperature from ut ut was read from the device via I2C and fed into the right calc path for either SMD500 or BMP085
ut | parameter ut read from device |
Definition at line 233 of file bmp085_bst.c.
unsigned long bmp085_get_up | ( | void | ) |
read out up for pressure conversion depending on the oversampling ratio setting up can be 16 to 19 bit
Definition at line 372 of file bmp085_bst.c.
unsigned short bmp085_get_ut | ( | void | ) |
read out ut for temperature conversion
Definition at line 328 of file bmp085_bst.c.
int bmp085_init | ( | bmp085_t * | bmp085 | ) |
BMP085_init
input : Pointer to bmp085_t output: - return: result of communication function notes :
initialize BMP085 / SMD500
This function initializes the BMP085 pressure sensor/ the successor SMD500 is also supported. The function automatically detects the sensor type and stores this for all future communication and calculation steps
*bmp085_t | pointer to bmp085 device data structure |
Definition at line 98 of file bmp085_bst.c.
char bmp085_set_reg | ( | unsigned | char, |
unsigned char * | , | ||
unsigned | char | ||
) |
int smd500_get_cal_param | ( | void | ) |
read out parameters cal_param from SMD500 memory This routine generates parameters from bitsliced data
Definition at line 209 of file bmp085_bst.c.