1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 20:35:33 +03:00
This commit is contained in:
jflyper 2017-06-11 02:14:47 +09:00
parent fac694ce4b
commit c40178dda1
5 changed files with 53 additions and 76 deletions

View file

@ -167,10 +167,10 @@ bool transponderIrInit(const transponderProvider_e provider)
}
switch (provider) {
case ARCITIMER:
case TRANSPONDER_ARCITIMER:
transponderIrInitArcitimer(&transponder);
break;
case ILAP:
case TRANSPONDER_ILAP:
transponderIrInitIlap(&transponder);
break;
case TRANSPONDER_ERLT:

Binary file not shown.

View file

@ -749,25 +749,27 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
break;
case MSP_TRANSPONDER_CONFIG: {
#define TRANSPONDER_SUPPORTED_MASK 0x01 // 00000001
#define TRANSPONDER_PROVIDER_MASK 0x0E // 00001110
#define TRANSPONDER_DATA_SIZE_MASK 0xF0 // 11110000
#define TRANSPONDER_PROVIDER_OFFSET 1
#define TRANSPONDER_DATA_SIZE_OFFSET 4
#ifdef TRANSPONDER
uint8_t header = 0;
// Backward compatibility to BFC 3.1.1 is lost for this message type
sbufWriteU8(dst, TRANSPONDER_PROVIDER_COUNT);
for (unsigned int i = 0; i < TRANSPONDER_PROVIDER_COUNT; i++) {
sbufWriteU8(dst, transponderRequirements[i].provider);
sbufWriteU8(dst, transponderRequirements[i].dataLength);
}
header |= 1 & TRANSPONDER_SUPPORTED_MASK;
header |= (transponderConfig()->provider << TRANSPONDER_PROVIDER_OFFSET) & TRANSPONDER_PROVIDER_MASK;
header |= ((sizeof(transponderConfig()->data) << TRANSPONDER_DATA_SIZE_OFFSET) & TRANSPONDER_DATA_SIZE_MASK);
uint8_t provider = transponderConfig()->provider;
sbufWriteU8(dst, provider);
sbufWriteU8(dst, header);
for (unsigned int i = 0; i < sizeof(transponderConfig()->data); i++) {
sbufWriteU8(dst, transponderConfig()->data[i]);
if (provider) {
uint8_t requirementIndex = provider - 1;
uint8_t providerDataLength = transponderRequirements[requirementIndex].dataLength;
for (unsigned int i = 0; i < providerDataLength; i++) {
sbufWriteU8(dst, transponderConfig()->data[i]);
}
}
#else
sbufWriteU8(dst, 0 & TRANSPONDER_SUPPORTED_MASK);
sbufWriteU8(dst, 0); // no providers
#endif
break;
}
@ -2000,30 +2002,36 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
switch (cmdMSP) {
#ifdef TRANSPONDER
case MSP_SET_TRANSPONDER_CONFIG:
{
uint8_t tmp = sbufReadU8(src);
case MSP_SET_TRANSPONDER_CONFIG: {
// Backward compatibility to BFC 3.1.1 is lost for this message type
uint8_t type;
switch(tmp){
case 0x02:
type = ILAP;
break;
case 0x04:
type = ARCITIMER;
break;
uint8_t provider = sbufReadU8(src);
uint8_t bytesRemaining = dataSize - 1;
if (provider > TRANSPONDER_PROVIDER_COUNT) {
return MSP_RESULT_ERROR;
}
if(type != transponderConfig()->provider){
const uint8_t requirementIndex = provider - 1;
const uint8_t transponderDataSize = transponderRequirements[requirementIndex].dataLength;
transponderConfigMutable()->provider = provider;
if (provider == TRANSPONDER_NONE) {
break;
}
if (bytesRemaining != transponderDataSize) {
return MSP_RESULT_ERROR;
}
if (provider != transponderConfig()->provider) {
transponderStopRepeating();
}
transponderConfigMutable()->provider = type;
memset(transponderConfigMutable()->data, 0, sizeof(transponderConfig()->data));
if (dataSize != sizeof(transponderConfig()->data) + 1) {
return MSP_RESULT_ERROR;
}
for (unsigned int i = 0; i < sizeof(transponderConfig()->data); i++) {
for (unsigned int i = 0; i < transponderDataSize; i++) {
transponderConfigMutable()->data[i] = sbufReadU8(src);
}
transponderUpdateData();

View file

@ -162,6 +162,11 @@ telemetry_ibus_unittest_SRC := \
$(USER_DIR)/telemetry/ibus.c
transponder_ir_unittest_SRC := \
$(USER_DIR)/drivers/transponder_ir_ilap.c \
$(USER_DIR)/drivers/transponder_ir_arcitimer.c
type_conversion_unittest_SRC := \
$(USER_DIR)/common/typeconversion.c
@ -169,9 +174,6 @@ type_conversion_unittest_SRC := \
ws2811_unittest_SRC := \
$(USER_DIR)/drivers/light_ws2811strip.c
# Please tweak the following variable definitions as needed by your
# project, except GTEST_HEADERS, which you can use in your own targets
# but shouldn't modify.
@ -356,43 +358,6 @@ $(OBJECT_DIR)/$1/$1 : $$($$1_OBJS) \
$(V1) mkdir -p $(dir $$@)
$(V1) $(CXX) $(CXX_FLAGS) $(PG_FLAGS) $$^ -o $$@
$(OBJECT_DIR)/drivers/transponder_ir_arcitimer.o : \
$(USER_DIR)/drivers/transponder_ir_arcitimer.c \
$(USER_DIR)/drivers/transponder_ir.h \
$(USER_DIR)/drivers/transponder_ir_arcitimer.h \
$(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/transponder_ir_arcitimer.c -o $@
$(OBJECT_DIR)/drivers/transponder_ir_ilap.o : \
$(USER_DIR)/drivers/transponder_ir_ilap.c \
$(USER_DIR)/drivers/transponder_ir.h \
$(USER_DIR)/drivers/transponder_ir_ilap.h \
$(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/transponder_ir_ilap.c -o $@
$(OBJECT_DIR)/transponder_unittest.o : \
$(TEST_DIR)/transponder_unittest.cc \
$(USER_DIR)/drivers/transponder_ir.h \
$(USER_DIR)/drivers/transponder_ir_arcitimer.h \
$(USER_DIR)/drivers/transponder_ir_ilap.h \
$(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/transponder_unittest.cc -o $@
$(OBJECT_DIR)/transponder_unittest : \
$(OBJECT_DIR)/drivers/transponder_ir_arcitimer.o \
$(OBJECT_DIR)/drivers/transponder_ir_ilap.o \
$(OBJECT_DIR)/transponder_unittest.o \
$(OBJECT_DIR)/gtest_main.a
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
test_$1: $(OBJECT_DIR)/$1/$1
$(V1) $$< $$(EXEC_OPTS) "$(STDOUT)" && echo "running $$@: PASS"

View file

@ -15,10 +15,10 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdlib.h>
#include <limits.h>
extern "C" {
#include <platform.h>
#include "build/build_config.h"
@ -27,11 +27,16 @@ extern "C" {
#include "drivers/transponder_ir_arcitimer.h"
#include "drivers/transponder_ir_ilap.h"
}
#include "unittest_macros.h"
#include "gtest/gtest.h"
extern "C" {
STATIC_UNIT_TESTED extern uint16_t dmaBufferOffset;
STATIC_UNIT_TESTED void updateTransponderDMABufferIlap(transponder_t *transponder, const uint8_t* transponderData);
STATIC_UNIT_TESTED void updateTransponderDMABufferArcitimer(transponder_t *transponder, const uint8_t* transponderData);
}
TEST(transponderTest, updateTransponderDMABufferArcitimer) {
//input
uint8_t data[9] = {0x1F, 0xFC, 0x8F, 0x3, 0xF0, 0x1, 0xF8, 0x1F, 0x0};
@ -63,6 +68,7 @@ TEST(transponderTest, updateTransponderDMABufferArcitimer) {
EXPECT_EQ(transponder.transponderIrDMABuffer.arcitimer[i], excepted[i]);
}
}
TEST(transponderTest, updateTransponderDMABufferIlap) {
uint8_t data[9] = {0x1F, 0xFC, 0x8F, 0x3, 0xF0, 0x1, 0x0, 0x0, 0x0};
@ -97,6 +103,4 @@ TEST(transponderTest, updateTransponderDMABufferIlap) {
for(i = 0; i < transponder.dma_buffer_size; i++) {
EXPECT_EQ(transponder.transponderIrDMABuffer.ilap[i], excepted[i]);
}
}