mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 05:15:25 +03:00
Touch up
This commit is contained in:
parent
fac694ce4b
commit
c40178dda1
5 changed files with 53 additions and 76 deletions
|
@ -167,10 +167,10 @@ bool transponderIrInit(const transponderProvider_e provider)
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (provider) {
|
switch (provider) {
|
||||||
case ARCITIMER:
|
case TRANSPONDER_ARCITIMER:
|
||||||
transponderIrInitArcitimer(&transponder);
|
transponderIrInitArcitimer(&transponder);
|
||||||
break;
|
break;
|
||||||
case ILAP:
|
case TRANSPONDER_ILAP:
|
||||||
transponderIrInitIlap(&transponder);
|
transponderIrInitIlap(&transponder);
|
||||||
break;
|
break;
|
||||||
case TRANSPONDER_ERLT:
|
case TRANSPONDER_ERLT:
|
||||||
|
|
Binary file not shown.
|
@ -749,25 +749,27 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_TRANSPONDER_CONFIG: {
|
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
|
#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;
|
uint8_t provider = transponderConfig()->provider;
|
||||||
header |= (transponderConfig()->provider << TRANSPONDER_PROVIDER_OFFSET) & TRANSPONDER_PROVIDER_MASK;
|
sbufWriteU8(dst, provider);
|
||||||
header |= ((sizeof(transponderConfig()->data) << TRANSPONDER_DATA_SIZE_OFFSET) & TRANSPONDER_DATA_SIZE_MASK);
|
|
||||||
|
|
||||||
sbufWriteU8(dst, header);
|
if (provider) {
|
||||||
for (unsigned int i = 0; i < sizeof(transponderConfig()->data); i++) {
|
uint8_t requirementIndex = provider - 1;
|
||||||
sbufWriteU8(dst, transponderConfig()->data[i]);
|
uint8_t providerDataLength = transponderRequirements[requirementIndex].dataLength;
|
||||||
|
|
||||||
|
for (unsigned int i = 0; i < providerDataLength; i++) {
|
||||||
|
sbufWriteU8(dst, transponderConfig()->data[i]);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
sbufWriteU8(dst, 0 & TRANSPONDER_SUPPORTED_MASK);
|
sbufWriteU8(dst, 0); // no providers
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -2000,30 +2002,36 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
|
|
||||||
switch (cmdMSP) {
|
switch (cmdMSP) {
|
||||||
#ifdef TRANSPONDER
|
#ifdef TRANSPONDER
|
||||||
case MSP_SET_TRANSPONDER_CONFIG:
|
case MSP_SET_TRANSPONDER_CONFIG: {
|
||||||
{
|
// Backward compatibility to BFC 3.1.1 is lost for this message type
|
||||||
uint8_t tmp = sbufReadU8(src);
|
|
||||||
|
|
||||||
uint8_t type;
|
uint8_t provider = sbufReadU8(src);
|
||||||
switch(tmp){
|
uint8_t bytesRemaining = dataSize - 1;
|
||||||
case 0x02:
|
|
||||||
type = ILAP;
|
if (provider > TRANSPONDER_PROVIDER_COUNT) {
|
||||||
break;
|
return MSP_RESULT_ERROR;
|
||||||
case 0x04:
|
|
||||||
type = ARCITIMER;
|
|
||||||
break;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
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();
|
transponderStopRepeating();
|
||||||
}
|
}
|
||||||
|
|
||||||
transponderConfigMutable()->provider = type;
|
memset(transponderConfigMutable()->data, 0, sizeof(transponderConfig()->data));
|
||||||
|
|
||||||
if (dataSize != sizeof(transponderConfig()->data) + 1) {
|
for (unsigned int i = 0; i < transponderDataSize; i++) {
|
||||||
return MSP_RESULT_ERROR;
|
|
||||||
}
|
|
||||||
for (unsigned int i = 0; i < sizeof(transponderConfig()->data); i++) {
|
|
||||||
transponderConfigMutable()->data[i] = sbufReadU8(src);
|
transponderConfigMutable()->data[i] = sbufReadU8(src);
|
||||||
}
|
}
|
||||||
transponderUpdateData();
|
transponderUpdateData();
|
||||||
|
|
|
@ -162,6 +162,11 @@ telemetry_ibus_unittest_SRC := \
|
||||||
$(USER_DIR)/telemetry/ibus.c
|
$(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 := \
|
type_conversion_unittest_SRC := \
|
||||||
$(USER_DIR)/common/typeconversion.c
|
$(USER_DIR)/common/typeconversion.c
|
||||||
|
|
||||||
|
@ -169,9 +174,6 @@ type_conversion_unittest_SRC := \
|
||||||
ws2811_unittest_SRC := \
|
ws2811_unittest_SRC := \
|
||||||
$(USER_DIR)/drivers/light_ws2811strip.c
|
$(USER_DIR)/drivers/light_ws2811strip.c
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
# Please tweak the following variable definitions as needed by your
|
# Please tweak the following variable definitions as needed by your
|
||||||
# project, except GTEST_HEADERS, which you can use in your own targets
|
# project, except GTEST_HEADERS, which you can use in your own targets
|
||||||
# but shouldn't modify.
|
# but shouldn't modify.
|
||||||
|
@ -356,43 +358,6 @@ $(OBJECT_DIR)/$1/$1 : $$($$1_OBJS) \
|
||||||
$(V1) mkdir -p $(dir $$@)
|
$(V1) mkdir -p $(dir $$@)
|
||||||
$(V1) $(CXX) $(CXX_FLAGS) $(PG_FLAGS) $$^ -o $$@
|
$(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
|
test_$1: $(OBJECT_DIR)/$1/$1
|
||||||
$(V1) $$< $$(EXEC_OPTS) "$(STDOUT)" && echo "running $$@: PASS"
|
$(V1) $$< $$(EXEC_OPTS) "$(STDOUT)" && echo "running $$@: PASS"
|
||||||
|
|
||||||
|
|
|
@ -15,10 +15,10 @@
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <limits.h>
|
#include <limits.h>
|
||||||
|
|
||||||
extern "C" {
|
extern "C" {
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
@ -27,11 +27,16 @@ extern "C" {
|
||||||
#include "drivers/transponder_ir_arcitimer.h"
|
#include "drivers/transponder_ir_arcitimer.h"
|
||||||
#include "drivers/transponder_ir_ilap.h"
|
#include "drivers/transponder_ir_ilap.h"
|
||||||
}
|
}
|
||||||
|
|
||||||
#include "unittest_macros.h"
|
#include "unittest_macros.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
extern "C" {
|
extern "C" {
|
||||||
STATIC_UNIT_TESTED extern uint16_t dmaBufferOffset;
|
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) {
|
TEST(transponderTest, updateTransponderDMABufferArcitimer) {
|
||||||
//input
|
//input
|
||||||
uint8_t data[9] = {0x1F, 0xFC, 0x8F, 0x3, 0xF0, 0x1, 0xF8, 0x1F, 0x0};
|
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]);
|
EXPECT_EQ(transponder.transponderIrDMABuffer.arcitimer[i], excepted[i]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST(transponderTest, updateTransponderDMABufferIlap) {
|
TEST(transponderTest, updateTransponderDMABufferIlap) {
|
||||||
uint8_t data[9] = {0x1F, 0xFC, 0x8F, 0x3, 0xF0, 0x1, 0x0, 0x0, 0x0};
|
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++) {
|
for(i = 0; i < transponder.dma_buffer_size; i++) {
|
||||||
EXPECT_EQ(transponder.transponderIrDMABuffer.ilap[i], excepted[i]);
|
EXPECT_EQ(transponder.transponderIrDMABuffer.ilap[i], excepted[i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
Loading…
Add table
Add a link
Reference in a new issue