Unit tests for BMP085

This commit is contained in:
Steveis 2015-06-30 17:33:44 +01:00
parent a9b5ad71b2
commit f0aec2e31d
5 changed files with 232 additions and 6 deletions

View File

@ -106,10 +106,10 @@ typedef struct {
#define SMD500_PARAM_MH -7357 //calibration parameter #define SMD500_PARAM_MH -7357 //calibration parameter
#define SMD500_PARAM_MI 3791 //calibration parameter #define SMD500_PARAM_MI 3791 //calibration parameter
static bmp085_t bmp085; STATIC_UNIT_TESTED bmp085_t bmp085;
static bool bmp085InitDone = false; static bool bmp085InitDone = false;
static uint16_t bmp085_ut; // static result of temperature measurement STATIC_UNIT_TESTED uint16_t bmp085_ut; // static result of temperature measurement
static uint32_t bmp085_up; // static result of pressure measurement STATIC_UNIT_TESTED uint32_t bmp085_up; // static result of pressure measurement
static void bmp085_get_cal_param(void); static void bmp085_get_cal_param(void);
static void bmp085_start_ut(void); static void bmp085_start_ut(void);
@ -118,7 +118,7 @@ static void bmp085_start_up(void);
static void bmp085_get_up(void); static void bmp085_get_up(void);
static int32_t bmp085_get_temperature(uint32_t ut); static int32_t bmp085_get_temperature(uint32_t ut);
static int32_t bmp085_get_pressure(uint32_t up); static int32_t bmp085_get_pressure(uint32_t up);
static void bmp085_calculate(int32_t *pressure, int32_t *temperature); STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature);
#ifdef BARO_XCLR_PIN #ifdef BARO_XCLR_PIN
#define BMP085_OFF digitalLo(BARO_XCLR_GPIO, BARO_XCLR_PIN); #define BMP085_OFF digitalLo(BARO_XCLR_GPIO, BARO_XCLR_PIN);
@ -337,9 +337,10 @@ static void bmp085_get_up(void)
>> (8 - bmp085.oversampling_setting); >> (8 - bmp085.oversampling_setting);
} }
static void bmp085_calculate(int32_t *pressure, int32_t *temperature) STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature)
{ {
int32_t temp, press; int32_t temp, press;
temp = bmp085_get_temperature(bmp085_ut); temp = bmp085_get_temperature(bmp085_ut);
press = bmp085_get_pressure(bmp085_up); press = bmp085_get_pressure(bmp085_up);
if (pressure) if (pressure)

View File

@ -27,3 +27,7 @@ typedef struct bmp085Config_s {
bool bmp085Detect(const bmp085Config_t *config, baro_t *baro); bool bmp085Detect(const bmp085Config_t *config, baro_t *baro);
void bmp085Disable(const bmp085Config_t *config); void bmp085Disable(const bmp085Config_t *config);
#ifdef UNIT_TEST
void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
#endif

View File

@ -59,7 +59,8 @@ TESTS = \
encoding_unittest \ encoding_unittest \
io_serial_unittest \ io_serial_unittest \
lowpass_unittest \ lowpass_unittest \
baro_unittest baro_unittest \
baro_bmp085_unittest
# All Google Test headers. Usually you shouldn't change this # All Google Test headers. Usually you shouldn't change this
# definition. # definition.
@ -487,6 +488,29 @@ baro_unittest : \
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
$(OBJECT_DIR)/drivers/barometer_bmp085.o : \
$(USER_DIR)/drivers/barometer_bmp085.c \
$(USER_DIR)/drivers/barometer_bmp085.h \
$(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/barometer_bmp085.c -o $@
$(OBJECT_DIR)/baro_bmp085_unittest.o : \
$(TEST_DIR)/baro_bmp085_unittest.cc \
$(USER_DIR)/drivers/barometer_bmp085.h \
$(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/baro_bmp085_unittest.cc -o $@
baro_bmp085_unittest : \
$(OBJECT_DIR)/drivers/barometer_bmp085.o \
$(OBJECT_DIR)/baro_bmp085_unittest.o \
$(OBJECT_DIR)/gtest_main.a
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
test: $(TESTS) test: $(TESTS)
set -e && for test in $(TESTS) ; do \ set -e && for test in $(TESTS) ; do \
$(OBJECT_DIR)/$$test; \ $(OBJECT_DIR)/$$test; \

View File

@ -0,0 +1,196 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
extern "C" {
void bmp085_calculate(int32_t *pressure, int32_t *temperature);
extern uint32_t bmp085_up;
extern uint16_t bmp085_ut;
typedef struct {
int16_t ac1;
int16_t ac2;
int16_t ac3;
uint16_t ac4;
uint16_t ac5;
uint16_t ac6;
int16_t b1;
int16_t b2;
int16_t mb;
int16_t mc;
int16_t md;
} bmp085_smd500_calibration_param_t;
typedef struct {
bmp085_smd500_calibration_param_t cal_param;
uint8_t mode;
uint8_t chip_id, ml_version, al_version;
uint8_t dev_addr;
int32_t param_b5;
int16_t oversampling_setting;
} bmp085_t;
bmp085_t bmp085;
}
#include "unittest_macros.h"
#include "gtest/gtest.h"
TEST(baroBmp085Test, TestBmp085CalculateOss0)
{
// given
int32_t pressure, temperature;
bmp085_up = 23843; // Digital pressure value
bmp085_ut = 27898; // Digital temperature value
// and
bmp085.cal_param.ac1 = 408;
bmp085.cal_param.ac2 = -72;
bmp085.cal_param.ac3 = -14383;
bmp085.cal_param.ac4 = 32741;
bmp085.cal_param.ac5 = 32757;
bmp085.cal_param.ac6 = 23153;
bmp085.cal_param.b1 = 6190;
bmp085.cal_param.b2 = 4;
bmp085.cal_param.mb = -32767;
bmp085.cal_param.mc = -8711;
bmp085.cal_param.md = 2868;
bmp085.oversampling_setting = 0;
// when
bmp085_calculate(&pressure, &temperature);
// then
EXPECT_EQ(69964, pressure); // Datasheet says 69965
EXPECT_EQ(1500, temperature);
}
TEST(baroBmp085Test, TestBmp085CalculateOss3)
{
// given
int32_t pressure, temperature;
bmp085_up = 271097; // Digital pressure value
bmp085_ut = 27898; // Digital temperature value
// and
bmp085.cal_param.ac1 = 408;
bmp085.cal_param.ac2 = -72;
bmp085.cal_param.ac3 = -14383;
bmp085.cal_param.ac4 = 32741;
bmp085.cal_param.ac5 = 32757;
bmp085.cal_param.ac6 = 23153;
bmp085.cal_param.b1 = 6190;
bmp085.cal_param.b2 = 4;
bmp085.cal_param.mb = -32767;
bmp085.cal_param.mc = -8711;
bmp085.cal_param.md = 2868;
bmp085.oversampling_setting = 3;
// when
bmp085_calculate(&pressure, &temperature);
// then
EXPECT_EQ(99998, pressure);
EXPECT_EQ(1500, temperature);
}
TEST(baroBmp085Test, TestBmp085CalculateOss3Cold)
{
// given
int32_t pressure, temperature;
bmp085_up = 271097; // Digital pressure value
bmp085_ut = 24342; // Digital temperature value 24342 = -20degC 27898 = 15degC
// and
bmp085.cal_param.ac1 = 408;
bmp085.cal_param.ac2 = -72;
bmp085.cal_param.ac3 = -14383;
bmp085.cal_param.ac4 = 32741;
bmp085.cal_param.ac5 = 32757;
bmp085.cal_param.ac6 = 23153;
bmp085.cal_param.b1 = 6190;
bmp085.cal_param.b2 = 4;
bmp085.cal_param.mb = -32767;
bmp085.cal_param.mc = -8711;
bmp085.cal_param.md = 2868;
bmp085.oversampling_setting = 3;
// when
bmp085_calculate(&pressure, &temperature);
// then
EXPECT_EQ(92251, pressure);
EXPECT_EQ(-2006, temperature); // -20.06 degC
}
TEST(baroBmp085Test, TestBmp085CalculateOss3Hot)
{
// given
int32_t pressure, temperature;
bmp085_up = 271097; // Digital pressure value
bmp085_ut = 33315; // Digital temperature value
// and
bmp085.cal_param.ac1 = 408;
bmp085.cal_param.ac2 = -72;
bmp085.cal_param.ac3 = -14383;
bmp085.cal_param.ac4 = 32741;
bmp085.cal_param.ac5 = 32757;
bmp085.cal_param.ac6 = 23153;
bmp085.cal_param.b1 = 6190;
bmp085.cal_param.b2 = 4;
bmp085.cal_param.mb = -32767;
bmp085.cal_param.mc = -8711;
bmp085.cal_param.md = 2868;
bmp085.oversampling_setting = 3;
// when
bmp085_calculate(&pressure, &temperature);
// then
EXPECT_EQ(108922, pressure);
EXPECT_EQ(5493, temperature); // 54.93 degC
}
// STUBS
extern "C" {
void gpioInit(){}
void RCC_APB2PeriphClockCmd(){}
void delay(uint32_t) {}
void delayMicroseconds(uint32_t) {}
bool i2cWrite(uint8_t, uint8_t, uint8_t) {
return 1;
}
bool i2cRead(uint8_t, uint8_t, uint8_t, uint8_t) {
return 1;
}
}

View File

@ -31,6 +31,7 @@
typedef enum typedef enum
{ {
Mode_TEST = 0x0, Mode_TEST = 0x0,
Mode_Out_PP = 0x10,
} GPIO_Mode; } GPIO_Mode;
typedef struct typedef struct