Skip to content

Commit

Permalink
Merge pull request iNavFlight#1176 from martinbudden/inav_sensorgyro_…
Browse files Browse the repository at this point in the history
…unittest

Added gyro sensor unit test
  • Loading branch information
martinbudden authored Jan 28, 2017
2 parents d590e45 + 33181b2 commit 6883f08
Show file tree
Hide file tree
Showing 7 changed files with 200 additions and 13 deletions.
2 changes: 2 additions & 0 deletions src/main/drivers/accgyro_fake.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#pragma once

#include "accgyro.h"

bool fakeAccDetect(accDev_t *acc);
void fakeAccSet(int16_t x, int16_t y, int16_t z);

Expand Down
16 changes: 11 additions & 5 deletions src/main/sensors/gyro.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@

#include "platform.h"

#include "build/build_config.h"

#include "common/axis.h"
#include "common/maths.h"
#include "common/filter.h"
Expand Down Expand Up @@ -65,9 +67,9 @@
#include "hardware_revision.h"
#endif

gyro_t gyro; // gyro access functions
gyro_t gyro; // gyro sensor object

static int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 };
STATIC_UNIT_TESTED int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 };

static uint16_t calibratingG = 0;

Expand Down Expand Up @@ -99,6 +101,7 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig,
.gyro_soft_notch_cutoff_2 = 1
);

#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_MPU6050)
static const extiConfig_t *selectMPUIntExtiConfig(void)
{
#if defined(MPU_INT_EXTI)
Expand All @@ -110,8 +113,9 @@ static const extiConfig_t *selectMPUIntExtiConfig(void)
return NULL;
#endif
}
#endif

static bool gyroDetect(gyroDev_t *dev, const extiConfig_t *extiConfig)
STATIC_UNIT_TESTED bool gyroDetect(gyroDev_t *dev, const extiConfig_t *extiConfig)
{
dev->mpuIntExtiConfig = extiConfig;

Expand Down Expand Up @@ -228,6 +232,8 @@ bool gyroInit(void)
const extiConfig_t *extiConfig = selectMPUIntExtiConfig();
mpuDetect(&gyro.dev);
mpuReset = gyro.dev.mpuConfiguration.reset;
#else
const extiConfig_t *extiConfig = NULL;
#endif

if (!gyroDetect(&gyro.dev, extiConfig)) {
Expand Down Expand Up @@ -310,7 +316,7 @@ static bool isOnFirstGyroCalibrationCycle(void)
return calibratingG == CALIBRATING_GYRO_CYCLES;
}

static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThreshold)
STATIC_UNIT_TESTED void performGyroCalibration(uint8_t gyroMovementCalibrationThreshold)
{
static int32_t g[3];
static stdev_t var[3];
Expand Down Expand Up @@ -363,7 +369,7 @@ void gyroUpdate(void)
gyro.gyroADC[Z] = gyro.dev.gyroADCRaw[Z];

if (!gyroIsCalibrationComplete()) {
performAcclerationCalibration(gyroConfig()->gyroMovementCalibrationThreshold);
performGyroCalibration(gyroConfig()->gyroMovementCalibrationThreshold);
}

for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
Expand Down
69 changes: 62 additions & 7 deletions src/test/Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -192,24 +192,24 @@ $(OBJECT_DIR)/maths_unittest : \
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@


$(OBJECT_DIR)/flight/gps_conversion.o : \
$(USER_DIR)/flight/gps_conversion.c \
$(USER_DIR)/flight/gps_conversion.h \
$(OBJECT_DIR)/common/gps_conversion.o : \
$(USER_DIR)/common/gps_conversion.c \
$(USER_DIR)/common/gps_conversion.h \
$(GTEST_HEADERS)

@mkdir -p $(dir $@)
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/gps_conversion.c -o $@
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/gps_conversion.c -o $@

$(OBJECT_DIR)/gps_conversion_unittest.o : \
$(TEST_DIR)/gps_conversion_unittest.cc \
$(USER_DIR)/flight/gps_conversion.h \
$(USER_DIR)/common/gps_conversion.h \
$(GTEST_HEADERS)

@mkdir -p $(dir $@)
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/gps_conversion_unittest.cc -o $@

$(OBJECT_DIR)/gps_conversion_unittest : \
$(OBJECT_DIR)/flight/gps_conversion.o \
$(OBJECT_DIR)/common/gps_conversion.o \
$(OBJECT_DIR)/gps_conversion_unittest.o \
$(OBJECT_DIR)/gtest_main.a

Expand All @@ -236,7 +236,7 @@ $(OBJECT_DIR)/telemetry_hott_unittest.o : \
$(OBJECT_DIR)/telemetry_hott_unittest : \
$(OBJECT_DIR)/telemetry/hott.o \
$(OBJECT_DIR)/telemetry_hott_unittest.o \
$(OBJECT_DIR)/flight/gps_conversion.o \
$(OBJECT_DIR)/common/gps_conversion.o \
$(OBJECT_DIR)/gtest_main.a

$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
Expand Down Expand Up @@ -577,6 +577,61 @@ $(OBJECT_DIR)/alignsensor_unittest : \

$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@

$(OBJECT_DIR)/build/debug.o : \
$(USER_DIR)/build/debug.c \
$(USER_DIR)/build/debug.h \
$(GTEST_HEADERS)

@mkdir -p $(dir $@)
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/build/debug.c -o $@

$(OBJECT_DIR)/drivers/gyro_sync.o : \
$(USER_DIR)/drivers/gyro_sync.c \
$(USER_DIR)/drivers/gyro_sync.h \
$(GTEST_HEADERS)

@mkdir -p $(dir $@)
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/gyro_sync.c -o $@

$(OBJECT_DIR)/drivers/accgyro_fake.o : \
$(USER_DIR)/drivers/accgyro_fake.c \
$(USER_DIR)/drivers/accgyro_fake.h \
$(GTEST_HEADERS)

@mkdir -p $(dir $@)
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/accgyro_fake.c -o $@

$(OBJECT_DIR)/sensors/gyro.o : \
$(USER_DIR)/sensors/gyro.c \
$(USER_DIR)/sensors/gyro.h \
$(GTEST_HEADERS)

@mkdir -p $(dir $@)
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/sensors/gyro.c -o $@

$(OBJECT_DIR)/sensor_gyro_unittest.o : \
$(TEST_DIR)/sensor_gyro_unittest.cc \
$(USER_DIR)/sensors/gyro.h \
$(GTEST_HEADERS)

@mkdir -p $(dir $@)
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/sensor_gyro_unittest.cc -o $@

$(OBJECT_DIR)/sensor_gyro_unittest : \
$(OBJECT_DIR)/build/debug.o \
$(OBJECT_DIR)/common/maths.o \
$(OBJECT_DIR)/common/filter.o \
$(OBJECT_DIR)/drivers/gyro_sync.o \
$(OBJECT_DIR)/drivers/accgyro_fake.o \
$(OBJECT_DIR)/sensors/gyro.o \
$(OBJECT_DIR)/sensors/boardalignment.o \
$(OBJECT_DIR)/sensor_gyro_unittest.o \
$(OBJECT_DIR)/gtest_main.a

$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@



test: $(TESTS:%=test-%)

test-%: $(OBJECT_DIR)/%
Expand Down
6 changes: 6 additions & 0 deletions src/test/unit/platform.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,12 @@ typedef struct
void* test;
} TIM_TypeDef;

typedef enum {
EXTI_Trigger_Rising = 0x08,
EXTI_Trigger_Falling = 0x0C,
EXTI_Trigger_Rising_Falling = 0x10
} EXTITrigger_TypeDef;

typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;

typedef enum {TEST_IRQ = 0 } IRQn_Type;
Expand Down
117 changes: 117 additions & 0 deletions src/test/unit/sensor_gyro_unittest.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,117 @@
/*
* 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>
#include <stdbool.h>

#include <limits.h>
#include <algorithm>

extern "C" {
#include <platform.h>

#include "build/build_config.h"
#include "build/debug.h"
#include "common/axis.h"
#include "common/utils.h"
#include "drivers/accgyro_fake.h"
#include "drivers/logging_codes.h"
#include "io/beeper.h"
#include "scheduler/scheduler.h"
#include "sensors/gyro.h"
#include "sensors/acceleration.h"
#include "sensors/sensors.h"

STATIC_UNIT_TESTED bool gyroDetect(gyroDev_t *dev, const extiConfig_t *extiConfig);
STATIC_UNIT_TESTED void performGyroCalibration(uint8_t gyroMovementCalibrationThreshold);
extern int32_t gyroZero[XYZ_AXIS_COUNT];
}

#include "unittest_macros.h"
#include "gtest/gtest.h"

TEST(SensorGyro, Detect)
{
const bool detected = gyroDetect(&gyro.dev, NULL);
EXPECT_EQ(true, detected);
EXPECT_EQ(GYRO_FAKE, detectedSensors[SENSOR_INDEX_GYRO]);
}

TEST(SensorGyro, Init)
{
gyroInit();
EXPECT_EQ(GYRO_FAKE, detectedSensors[SENSOR_INDEX_GYRO]);
}

TEST(SensorGyro, Read)
{
gyroInit();
fakeGyroSet(5, 6, 7);
const bool read = gyro.dev.read(&gyro.dev);
EXPECT_EQ(true, read);
EXPECT_EQ(5, gyro.dev.gyroADCRaw[X]);
EXPECT_EQ(6, gyro.dev.gyroADCRaw[Y]);
EXPECT_EQ(7, gyro.dev.gyroADCRaw[Z]);
}

TEST(SensorGyro, Calibrate)
{
gyroSetCalibrationCycles(CALIBRATING_GYRO_CYCLES);
gyroInit();
fakeGyroSet(5, 6, 7);
const bool read = gyro.dev.read(&gyro.dev);
EXPECT_EQ(true, read);
gyro.gyroADC[X] = gyro.dev.gyroADCRaw[X];
gyro.gyroADC[Y] = gyro.dev.gyroADCRaw[Y];
gyro.gyroADC[Z] = gyro.dev.gyroADCRaw[Z];
EXPECT_EQ(5, gyro.gyroADC[X]);
EXPECT_EQ(6, gyro.gyroADC[Y]);
EXPECT_EQ(7, gyro.gyroADC[Z]);
static const int gyroMovementCalibrationThreshold = 32;
gyroZero[X] = 8;
gyroZero[Y] = 9;
gyroZero[Z] = 10;
performGyroCalibration(gyroMovementCalibrationThreshold);
EXPECT_EQ(0, gyroZero[X]);
EXPECT_EQ(0, gyroZero[Y]);
EXPECT_EQ(0, gyroZero[Z]);
EXPECT_EQ(false, gyroIsCalibrationComplete());
while (!gyroIsCalibrationComplete()) {
performGyroCalibration(gyroMovementCalibrationThreshold);
gyro.gyroADC[X] = gyro.dev.gyroADCRaw[X];
gyro.gyroADC[Y] = gyro.dev.gyroADCRaw[Y];
gyro.gyroADC[Z] = gyro.dev.gyroADCRaw[Z];
}
EXPECT_EQ(5, gyroZero[X]);
EXPECT_EQ(6, gyroZero[Y]);
EXPECT_EQ(7, gyroZero[Z]);
}


// STUBS

extern "C" {

uint32_t micros(void) {return 0;}
void beeper(beeperMode_e) {}
uint8_t detectedSensors[] = { GYRO_NONE, ACC_NONE };
void addBootlogEvent6(bootLogEventCode_e eventCode, uint16_t eventFlags, uint16_t param1, uint16_t param2, uint16_t param3, uint16_t param4)
{UNUSED(eventCode);UNUSED(eventFlags);UNUSED(param1);UNUSED(param2);UNUSED(param3);UNUSED(param4);}
timeDelta_t getGyroUpdateRate(void) {return gyro.targetLooptime;}
void sensorsSet(uint32_t) {}
void schedulerResetTaskStatistics(cfTaskId_e) {}
}
1 change: 1 addition & 0 deletions src/test/unit/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#define LED_STRIP
#define USE_SERVOS
#define TRANSPONDER
#define USE_FAKE_GYRO
#define USE_VCP
#define USE_UART1
#define USE_UART2
Expand Down
2 changes: 1 addition & 1 deletion src/test/unit/telemetry_hott_unittest.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ extern "C" {
#include "build/debug.h"

#include "common/axis.h"
#include "common/gps_conversion.h"

#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
Expand All @@ -44,7 +45,6 @@ extern "C" {
#include "telemetry/hott.h"

#include "flight/pid.h"
#include "flight/gps_conversion.h"

#include "fc/runtime_config.h"

Expand Down

0 comments on commit 6883f08

Please sign in to comment.