Add first unit test for some code in serial.c. Fix compiler warnings in

other tests.
This commit is contained in:
Dominic Clifton 2015-04-01 14:07:27 +01:00
parent 8a9d2e3708
commit b0b1eaf9c7
10 changed files with 164 additions and 61 deletions

View File

@ -17,7 +17,7 @@
#pragma once
#ifdef STM32F10X
#if defined(STM32F10X) || defined(UNIT_TEST)
typedef enum
{
Mode_AIN = 0x0,

View File

@ -45,6 +45,41 @@
#define MAX_SOFTSERIAL_PORTS 1
#endif
typedef struct softSerial_s {
serialPort_t port;
const timerHardware_t *rxTimerHardware;
volatile uint8_t rxBuffer[SOFTSERIAL_BUFFER_SIZE];
const timerHardware_t *txTimerHardware;
volatile uint8_t txBuffer[SOFTSERIAL_BUFFER_SIZE];
uint8_t isSearchingForStartBit;
uint8_t rxBitIndex;
uint8_t rxLastLeadingEdgeAtBitIndex;
uint8_t rxEdge;
uint8_t isTransmittingData;
int8_t bitsLeftToTransmit;
uint16_t internalTxBuffer; // includes start and stop bits
uint16_t internalRxBuffer; // includes start and stop bits
uint16_t transmissionErrors;
uint16_t receiveErrors;
uint8_t softSerialPortIndex;
timerCCHandlerRec_t timerCb;
timerCCHandlerRec_t edgeCb;
} softSerial_t;
extern timerHardware_t* serialTimerHardware;
extern softSerial_t softSerialPorts[];
extern const struct serialPortVTable softSerialVTable[];
softSerial_t softSerialPorts[MAX_SOFTSERIAL_PORTS];
void onSerialTimer(timerCCHandlerRec_t *cbRec, captureCompare_t capture);

View File

@ -24,40 +24,6 @@ typedef enum {
SOFTSERIAL2
} softSerialPortIndex_e;
typedef struct softSerial_s {
serialPort_t port;
const timerHardware_t *rxTimerHardware;
volatile uint8_t rxBuffer[SOFTSERIAL_BUFFER_SIZE];
const timerHardware_t *txTimerHardware;
volatile uint8_t txBuffer[SOFTSERIAL_BUFFER_SIZE];
uint8_t isSearchingForStartBit;
uint8_t rxBitIndex;
uint8_t rxLastLeadingEdgeAtBitIndex;
uint8_t rxEdge;
uint8_t isTransmittingData;
int8_t bitsLeftToTransmit;
uint16_t internalTxBuffer; // includes start and stop bits
uint16_t internalRxBuffer; // includes start and stop bits
uint16_t transmissionErrors;
uint16_t receiveErrors;
uint8_t softSerialPortIndex;
timerCCHandlerRec_t timerCb;
timerCCHandlerRec_t edgeCb;
} softSerial_t;
extern timerHardware_t* serialTimerHardware;
extern softSerial_t softSerialPorts[];
extern const struct serialPortVTable softSerialVTable[];
serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr callback, uint32_t baud, portOptions_t options);
// serialPort API

View File

@ -27,12 +27,18 @@
#include "common/utils.h"
#include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/serial.h"
#if defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)
#include "drivers/serial_softserial.h"
#endif
#if defined(USE_USART1) || defined(USE_USART2) || defined(USE_USART3)
#include "drivers/serial_uart.h"
#endif
#if defined(USE_VCP)
#include "drivers/serial_usb_vcp.h"
#endif
#include "io/serial.h"
#include "serial_cli.h"

View File

@ -60,7 +60,7 @@ typedef enum {
SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_SOFTSERIAL2
} serialPortIdentifier_e;
serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT];
extern serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT];
//
// runtime

View File

@ -1611,7 +1611,7 @@ static void cliVersion(char *cmdline)
);
}
void cliProcess()
void cliProcess(void)
{
if (!cliPort) {
return;

View File

@ -55,6 +55,7 @@ TESTS = \
ledstrip_unittest \
ws2811_unittest \
encoding_unittest \
io_serial_unittest \
lowpass_unittest
# All Google Test headers. Usually you shouldn't change this
@ -389,6 +390,28 @@ flight_mixer_unittest : \
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
$(OBJECT_DIR)/io/serial.o : \
$(USER_DIR)/io/serial.c \
$(USER_DIR)/io/serial.h \
$(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/serial.c -o $@
$(OBJECT_DIR)/io_serial_unittest.o : \
$(TEST_DIR)/io_serial_unittest.cc \
$(USER_DIR)/io/serial.h \
$(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/io_serial_unittest.cc -o $@
io_serial_unittest : \
$(OBJECT_DIR)/io/serial.o \
$(OBJECT_DIR)/io_serial_unittest.o \
$(OBJECT_DIR)/gtest_main.a
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
test: $(TESTS)
set -e && for test in $(TESTS) ; do \

View File

@ -71,17 +71,17 @@ TEST(AltitudeHoldTest, IsThrustFacingDownwards)
// given
inclinationExpectation_t inclinationExpectations[] = {
{ { 0, 0 }, DOWNWARDS_THRUST },
{ { 799, 799 }, DOWNWARDS_THRUST },
{ { 800, 799 }, UPWARDS_THRUST },
{ { 799, 800 }, UPWARDS_THRUST },
{ { 800, 800 }, UPWARDS_THRUST },
{ { 801, 801 }, UPWARDS_THRUST },
{ { -799, -799 }, DOWNWARDS_THRUST },
{ { -800, -799 }, UPWARDS_THRUST },
{ { -799, -800 }, UPWARDS_THRUST },
{ { -800, -800 }, UPWARDS_THRUST },
{ { -801, -801 }, UPWARDS_THRUST }
{ {{ 0, 0 }}, DOWNWARDS_THRUST },
{ {{ 799, 799 }}, DOWNWARDS_THRUST },
{ {{ 800, 799 }}, UPWARDS_THRUST },
{ {{ 799, 800 }}, UPWARDS_THRUST },
{ {{ 800, 800 }}, UPWARDS_THRUST },
{ {{ 801, 801 }}, UPWARDS_THRUST },
{ {{ -799, -799 }}, DOWNWARDS_THRUST },
{ {{ -800, -799 }}, UPWARDS_THRUST },
{ {{ -799, -800 }}, UPWARDS_THRUST },
{ {{ -800, -800 }}, UPWARDS_THRUST },
{ {{ -801, -801 }}, UPWARDS_THRUST }
};
uint8_t testIterationCount = sizeof(inclinationExpectations) / sizeof(inclinationExpectation_t);
@ -105,18 +105,18 @@ typedef struct inclinationAngleExpectations_s {
TEST(AltitudeHoldTest, TestCalculateTiltAngle)
{
inclinationAngleExpectations_t inclinationAngleExpectations[] = {
{ {0, 0}, 0},
{ {1, 0}, 1},
{ {0, 1}, 1},
{ {0, -1}, 1},
{ {-1, 0}, 1},
{ {-1, -2}, 2},
{ {-2, -1}, 2},
{ {1, 2}, 2},
{ {2, 1}, 2}
{ {{ 0, 0}}, 0},
{ {{ 1, 0}}, 1},
{ {{ 0, 1}}, 1},
{ {{ 0, -1}}, 1},
{ {{-1, 0}}, 1},
{ {{-1, -2}}, 2},
{ {{-2, -1}}, 2},
{ {{ 1, 2}}, 2},
{ {{ 2, 1}}, 2}
};
rollAndPitchInclination_t inclination = {0, 0};
rollAndPitchInclination_t inclination = {{0, 0}};
uint16_t tilt_angle = calculateTiltAngle(&inclination);
EXPECT_EQ(tilt_angle, 0);

View File

@ -0,0 +1,73 @@
/*
* 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>
extern "C" {
#include "platform.h"
#include "drivers/serial.h"
#include "io/serial.h"
void serialInit(serialConfig_t *initialSerialConfig);
}
#include "unittest_macros.h"
#include "gtest/gtest.h"
//uint32_t testFeatureMask = 0;
uint8_t cliMode = 0;
TEST(IoSerialTest, TestFindPortConfig)
{
// given
serialConfig_t serialConfig;
memset(&serialConfig, 0, sizeof(serialConfig));
// when
serialInit(&serialConfig);
// and
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);
// then
EXPECT_EQ(NULL, portConfig);
}
// STUBS
extern "C" {
//
//bool feature(uint32_t mask) {
// return (mask & testFeatureMask);
//}s
void delay(uint32_t) {}
void cliEnter(serialPort_t *) {}
void cliProcess(void) {}
bool isSerialTransmitBufferEmpty(serialPort_t *) {
return true;
}
void mspProcess(void) {}
void systemResetToBootloader(void) {}
}

View File

@ -418,6 +418,6 @@ int scaleRange(int x, int srcMin, int srcMax, int destMin, int destMax) {
return 0;
}
bool failsafeHasTimerElapsed(void) { }
bool failsafeHasTimerElapsed(void) { return false; }
}