1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 00:05:33 +03:00

Merge branch 'development' of https://github.com/borisbstyle/betaflight into development

This commit is contained in:
borisbstyle 2016-08-13 22:27:47 +02:00
commit 70c8493b95
17 changed files with 242 additions and 155 deletions

108
Makefile
View file

@ -37,6 +37,20 @@ SERIAL_DEVICE ?= $(firstword $(wildcard /dev/ttyUSB*) no-port-found)
# Flash size (KB). Some low-end chips actually have more flash than advertised, use this to override.
FLASH_SIZE ?=
## Set verbosity level based on the V= parameter
## V=0 Low
## v=1 High
export AT := @
ifndef V
export V0 :=
export V1 := $(AT)
else ifeq ($(V), 0)
export V0 := $(AT)
export V1 := $(AT)
else ifeq ($(V), 1)
endif
###############################################################################
# Things that need to be maintained as the source changes
#
@ -640,39 +654,39 @@ CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
# It would be nice to compute these lists, but that seems to be just beyond make.
$(TARGET_HEX): $(TARGET_ELF)
$(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
$(V0) $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
$(TARGET_BIN): $(TARGET_ELF)
$(OBJCOPY) -O binary $< $@
$(V0) $(OBJCOPY) -O binary $< $@
$(TARGET_ELF): $(TARGET_OBJS)
@echo LD $(notdir $@)
@$(CC) -o $@ $^ $(LDFLAGS)
$(SIZE) $(TARGET_ELF)
$(V1) echo LD $(notdir $@)
$(V1) $(CC) -o $@ $^ $(LDFLAGS)
$(V0) $(SIZE) $(TARGET_ELF)
# Compile
$(OBJECT_DIR)/$(TARGET)/%.o: %.c
@mkdir -p $(dir $@)
@echo %% $(notdir $<)
@$(CC) -c -o $@ $(CFLAGS) $<
$(V1) mkdir -p $(dir $@)
$(V1) echo %% $(notdir $<)
$(V1) $(CC) -c -o $@ $(CFLAGS) $<
# Assemble
$(OBJECT_DIR)/$(TARGET)/%.o: %.s
@mkdir -p $(dir $@)
@echo %% $(notdir $<)
@$(CC) -c -o $@ $(ASFLAGS) $<
$(V1) mkdir -p $(dir $@)
$(V1) echo %% $(notdir $<)
$(V1) $(CC) -c -o $@ $(ASFLAGS) $<
$(OBJECT_DIR)/$(TARGET)/%.o: %.S
@mkdir -p $(dir $@)
@echo %% $(notdir $<)
@$(CC) -c -o $@ $(ASFLAGS) $<
$(V1) mkdir -p $(dir $@)
$(V1) echo %% $(notdir $<)
$(V1) $(CC) -c -o $@ $(ASFLAGS) $<
## all : Build all valid targets
all: $(VALID_TARGETS)
$(VALID_TARGETS):
echo "" && \
$(V0) echo "" && \
echo "Building $@" && \
$(MAKE) binary hex TARGET=$@ && \
echo "Building $@ succeeded."
@ -684,22 +698,22 @@ TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
## clean : clean up temporary / machine-generated files
clean:
echo "Cleaning $(TARGET)"
rm -f $(CLEAN_ARTIFACTS)
rm -rf $(OBJECT_DIR)/$(TARGET)
echo "Cleaning $(TARGET) succeeded."
$(V0) echo "Cleaning $(TARGET)"
$(V0) rm -f $(CLEAN_ARTIFACTS)
$(V0) rm -rf $(OBJECT_DIR)/$(TARGET)
$(V0) echo "Cleaning $(TARGET) succeeded."
## clean_test : clean up temporary / machine-generated files (tests)
clean_test:
cd src/test && $(MAKE) clean || true
$(V0) cd src/test && $(MAKE) clean || true
## clean_<TARGET> : clean up one specific target
$(CLEAN_TARGETS) :
$(MAKE) -j TARGET=$(subst clean_,,$@) clean
$(V0) $(MAKE) -j TARGET=$(subst clean_,,$@) clean
## <TARGET>_clean : clean up one specific target (alias for above)
$(TARGETS_CLEAN) :
$(MAKE) -j TARGET=$(subst _clean,,$@) clean
$(V0) $(MAKE) -j TARGET=$(subst _clean,,$@) clean
## clean_all : clean all valid targets
clean_all:$(CLEAN_TARGETS)
@ -709,62 +723,62 @@ all_clean:$(TARGETS_CLEAN)
flash_$(TARGET): $(TARGET_HEX)
stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
echo -n 'R' >$(SERIAL_DEVICE)
stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
$(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
$(V0) echo -n 'R' >$(SERIAL_DEVICE)
$(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
## flash : flash firmware (.hex) onto flight controller
flash: flash_$(TARGET)
st-flash_$(TARGET): $(TARGET_BIN)
st-flash --reset write $< 0x08000000
$(V0) st-flash --reset write $< 0x08000000
## st-flash : flash firmware (.bin) onto flight controller
st-flash: st-flash_$(TARGET)
binary:
$(MAKE) -j $(TARGET_BIN)
$(V0) $(MAKE) -j $(TARGET_BIN)
hex:
$(MAKE) -j $(TARGET_HEX)
$(V0) $(MAKE) -j $(TARGET_HEX)
unbrick_$(TARGET): $(TARGET_HEX)
stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
$(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
$(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
## unbrick : unbrick flight controller
unbrick: unbrick_$(TARGET)
## cppcheck : run static analysis on C source code
cppcheck: $(CSOURCES)
$(CPPCHECK)
$(V0) $(CPPCHECK)
cppcheck-result.xml: $(CSOURCES)
$(CPPCHECK) --xml-version=2 2> cppcheck-result.xml
$(V0) $(CPPCHECK) --xml-version=2 2> cppcheck-result.xml
## help : print this help message and exit
help: Makefile
@echo ""
@echo "Makefile for the $(FORKNAME) firmware"
@echo ""
@echo "Usage:"
@echo " make [TARGET=<target>] [OPTIONS=\"<options>\"]"
@echo "Or:"
@echo " make <target> [OPTIONS=\"<options>\"]"
@echo ""
@echo "Valid TARGET values are: $(VALID_TARGETS)"
@echo ""
@sed -n 's/^## //p' $<
$(V0) @echo ""
$(V0) @echo "Makefile for the $(FORKNAME) firmware"
$(V0) @echo ""
$(V0) @echo "Usage:"
$(V0) @echo " make [V=<verbosity>] [TARGET=<target>] [OPTIONS=\"<options>\"]"
$(V0) @echo "Or:"
$(V0) @echo " make <target> [V=<verbosity>] [OPTIONS=\"<options>\"]"
$(V0) @echo ""
$(V0) @echo "Valid TARGET values are: $(VALID_TARGETS)"
$(V0) @echo ""
$(V0) @sed -n 's/^## //p' $<
## targets : print a list of all valid target platforms (for consumption by scripts)
targets:
@echo "Valid targets: $(VALID_TARGETS)"
@echo "Target: $(TARGET)"
@echo "Base target: $(BASE_TARGET)"
$(V0) @echo "Valid targets: $(VALID_TARGETS)"
$(V0) @echo "Target: $(TARGET)"
$(V0) @echo "Base target: $(BASE_TARGET)"
## test : run the cleanflight test suite
test:
cd src/test && $(MAKE) test || true
$(V0) cd src/test && $(MAKE) test || true
# rebuild everything when makefile changes
$(TARGET_OBJS) : Makefile

View file

@ -17,6 +17,7 @@
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <math.h>
#include "common/filter.h"
@ -137,3 +138,32 @@ float filterApplyAveragef(float input, uint8_t averageCount, float averageState[
return averageSum / averageCount;
}
// FIR filter
void firFilterInit2(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs, uint8_t coeffsLength)
{
filter->buf = buf;
filter->bufLength = bufLength;
filter->coeffs = coeffs;
filter->coeffsLength = coeffsLength;
memset(filter->buf, 0, sizeof(float) * filter->bufLength);
}
void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs)
{
firFilterInit2(filter, buf, bufLength, coeffs, bufLength);
}
void firFilterUpdate(firFilter_t *filter, float input)
{
memmove(&filter->buf[1], &filter->buf[0], (filter->bufLength-1) * sizeof(float));
filter->buf[0] = input;
}
float firFilterApply(firFilter_t *filter)
{
float ret = 0.0f;
for (int ii = 0; ii < filter->coeffsLength; ++ii) {
ret += filter->coeffs[ii] * filter->buf[ii];
}
return ret;
}

View file

@ -32,6 +32,7 @@ typedef struct biquadFilter_s {
typedef enum {
FILTER_PT1 = 0,
FILTER_BIQUAD,
FILTER_FIR,
} filterType_e;
typedef enum {
@ -39,6 +40,13 @@ typedef enum {
FILTER_NOTCH
} biquadFilterType_e;
typedef struct firFilter_s {
float *buf;
const float *coeffs;
uint8_t bufLength;
uint8_t coeffsLength;
} firFilter_t;
void biquadFilterInitLPF(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate);
void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, biquadFilterType_e filterType);
float biquadFilterApply(biquadFilter_t *filter, float input);
@ -51,3 +59,8 @@ float pt1FilterApply4(pt1Filter_t *filter, float input, uint8_t f_cut, float dT)
int32_t filterApplyAverage(int32_t input, uint8_t averageCount, int32_t averageState[DELTA_MAX_SAMPLES]);
float filterApplyAveragef(float input, uint8_t averageCount, float averageState[DELTA_MAX_SAMPLES]);
void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs);
void firFilterInit2(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs, uint8_t coeffsLength);
void firFilterUpdate(firFilter_t *filter, float input);
float firFilterApply(firFilter_t *filter);

View file

@ -61,7 +61,7 @@ uint32_t serialRxBytesWaiting(serialPort_t *instance)
return instance->vTable->serialTotalRxWaiting(instance);
}
uint8_t serialTxBytesFree(serialPort_t *instance)
uint32_t serialTxBytesFree(serialPort_t *instance)
{
return instance->vTable->serialTotalTxFree(instance);
}

View file

@ -63,7 +63,7 @@ struct serialPortVTable {
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
uint32_t (*serialTotalRxWaiting)(serialPort_t *instance);
uint8_t (*serialTotalTxFree)(serialPort_t *instance);
uint32_t (*serialTotalTxFree)(serialPort_t *instance);
uint8_t (*serialRead)(serialPort_t *instance);
@ -82,7 +82,7 @@ struct serialPortVTable {
void serialWrite(serialPort_t *instance, uint8_t ch);
uint32_t serialRxBytesWaiting(serialPort_t *instance);
uint8_t serialTxBytesFree(serialPort_t *instance);
uint32_t serialTxBytesFree(serialPort_t *instance);
void serialWriteBuf(serialPort_t *instance, uint8_t *data, int count);
uint8_t serialRead(serialPort_t *instance);
void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate);

View file

@ -412,7 +412,7 @@ uint32_t softSerialRxBytesWaiting(serialPort_t *instance)
return (s->port.rxBufferHead - s->port.rxBufferTail) & (s->port.rxBufferSize - 1);
}
uint8_t softSerialTxBytesFree(serialPort_t *instance)
uint32_t softSerialTxBytesFree(serialPort_t *instance)
{
if ((instance->mode & MODE_TX) == 0) {
return 0;

View file

@ -29,7 +29,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
// serialPort API
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);
uint32_t softSerialRxBytesWaiting(serialPort_t *instance);
uint8_t softSerialTxBytesFree(serialPort_t *instance);
uint32_t softSerialTxBytesFree(serialPort_t *instance);
uint8_t softSerialReadByte(serialPort_t *instance);
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate);
bool isSoftSerialTransmitBufferEmpty(serialPort_t *s);

View file

@ -315,7 +315,7 @@ uint32_t uartTotalRxBytesWaiting(serialPort_t *instance)
}
}
uint8_t uartTotalTxBytesFree(serialPort_t *instance)
uint32_t uartTotalTxBytesFree(serialPort_t *instance)
{
uartPort_t *s = (uartPort_t*)instance;

View file

@ -66,7 +66,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
// serialPort API
void uartWrite(serialPort_t *instance, uint8_t ch);
uint32_t uartTotalRxBytesWaiting(serialPort_t *instance);
uint8_t uartTotalTxBytesFree(serialPort_t *instance);
uint32_t uartTotalTxBytesFree(serialPort_t *instance);
uint8_t uartRead(serialPort_t *instance);
void uartSetBaudRate(serialPort_t *s, uint32_t baudRate);
bool isUartTransmitBufferEmpty(serialPort_t *s);

View file

@ -69,7 +69,7 @@ static uint32_t usbVcpAvailable(serialPort_t *instance)
{
UNUSED(instance);
return receiveLength;
return CDC_Receive_BytesAvailable();
}
static uint8_t usbVcpRead(serialPort_t *instance)
@ -150,10 +150,9 @@ static void usbVcpBeginWrite(serialPort_t *instance)
port->buffering = true;
}
uint8_t usbTxBytesFree()
uint32_t usbTxBytesFree()
{
// Because we block upon transmit and don't buffer bytes, our "buffer" capacity is effectively unlimited.
return 255;
return CDC_Send_FreeBytes();
}
static void usbVcpEndWrite(serialPort_t *instance)

View file

@ -1000,8 +1000,8 @@ static void printRxFail(uint8_t dumpMask, master_t *defaultConfig)
for (uint8_t channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[channel];
channelFailsafeConfigurationDefault = &defaultConfig->rxConfig.failsafe_channel_configurations[channel];
equalsDefault = channelFailsafeConfiguration->mode == channelFailsafeConfigurationDefault->mode
&& channelFailsafeConfiguration->step == channelFailsafeConfigurationDefault->step;
equalsDefault = channelFailsafeConfiguration->mode == channelFailsafeConfigurationDefault->mode
&& channelFailsafeConfiguration->step == channelFailsafeConfigurationDefault->step;
requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
if (requireValue) {
@ -1113,9 +1113,9 @@ static void printAux(uint8_t dumpMask, master_t *defaultConfig)
mac = &masterConfig.modeActivationConditions[i];
macDefault = &defaultConfig->modeActivationConditions[i];
equalsDefault = mac->modeId == macDefault->modeId
&& mac->auxChannelIndex == macDefault->auxChannelIndex
&& mac->range.startStep == macDefault->range.startStep
&& mac->range.endStep == macDefault->range.endStep;
&& mac->auxChannelIndex == macDefault->auxChannelIndex
&& mac->range.startStep == macDefault->range.startStep
&& mac->range.endStep == macDefault->range.endStep;
cliDumpPrintf(dumpMask, equalsDefault, "aux %u %u %u %u %u\r\n",
i,
mac->modeId,
@ -1172,17 +1172,17 @@ static void printSerial(uint8_t dumpMask, master_t *defaultConfig)
serialConfig_t *serialConfigDefault;
bool equalsDefault;
for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
serialConfig = &masterConfig.serialConfig;
serialConfig = &masterConfig.serialConfig;
if (!serialIsPortAvailable(serialConfig->portConfigs[i].identifier)) {
continue;
};
serialConfigDefault = &defaultConfig->serialConfig;
equalsDefault = serialConfig->portConfigs[i].identifier == serialConfigDefault->portConfigs[i].identifier
&& serialConfig->portConfigs[i].functionMask == serialConfigDefault->portConfigs[i].functionMask
&& serialConfig->portConfigs[i].msp_baudrateIndex == serialConfigDefault->portConfigs[i].msp_baudrateIndex
&& serialConfig->portConfigs[i].gps_baudrateIndex == serialConfigDefault->portConfigs[i].gps_baudrateIndex
&& serialConfig->portConfigs[i].telemetry_baudrateIndex == serialConfigDefault->portConfigs[i].telemetry_baudrateIndex
&& serialConfig->portConfigs[i].blackbox_baudrateIndex == serialConfigDefault->portConfigs[i].blackbox_baudrateIndex;
serialConfigDefault = &defaultConfig->serialConfig;
equalsDefault = serialConfig->portConfigs[i].identifier == serialConfigDefault->portConfigs[i].identifier
&& serialConfig->portConfigs[i].functionMask == serialConfigDefault->portConfigs[i].functionMask
&& serialConfig->portConfigs[i].msp_baudrateIndex == serialConfigDefault->portConfigs[i].msp_baudrateIndex
&& serialConfig->portConfigs[i].gps_baudrateIndex == serialConfigDefault->portConfigs[i].gps_baudrateIndex
&& serialConfig->portConfigs[i].telemetry_baudrateIndex == serialConfigDefault->portConfigs[i].telemetry_baudrateIndex
&& serialConfig->portConfigs[i].blackbox_baudrateIndex == serialConfigDefault->portConfigs[i].blackbox_baudrateIndex;
cliDumpPrintf(dumpMask, equalsDefault, "serial %d %d %ld %ld %ld %ld\r\n" ,
serialConfig->portConfigs[i].identifier,
serialConfig->portConfigs[i].functionMask,
@ -1190,7 +1190,7 @@ static void printSerial(uint8_t dumpMask, master_t *defaultConfig)
baudRates[serialConfig->portConfigs[i].gps_baudrateIndex],
baudRates[serialConfig->portConfigs[i].telemetry_baudrateIndex],
baudRates[serialConfig->portConfigs[i].blackbox_baudrateIndex]
);
);
}
}
@ -1202,7 +1202,7 @@ static void cliSerial(char *cmdline)
if (isEmpty(cmdline)) {
printSerial(DUMP_MASTER, &masterConfig);
return;
return;
}
serialPortConfig_t portConfig;
memset(&portConfig, 0 , sizeof(portConfig));
@ -1358,11 +1358,11 @@ static void printAdjustmentRange(uint8_t dumpMask, master_t *defaultConfig)
for (int i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
ar = &masterConfig.adjustmentRanges[i];
arDefault = &defaultConfig->adjustmentRanges[i];
equalsDefault = ar->auxChannelIndex == arDefault->auxChannelIndex
&& ar->range.startStep == arDefault->range.startStep
&& ar->range.endStep == arDefault->range.endStep
&& ar->adjustmentFunction == arDefault->adjustmentFunction
&& ar->auxSwitchChannelIndex == arDefault->auxSwitchChannelIndex
equalsDefault = ar->auxChannelIndex == arDefault->auxChannelIndex
&& ar->range.startStep == arDefault->range.startStep
&& ar->range.endStep == arDefault->range.endStep
&& ar->adjustmentFunction == arDefault->adjustmentFunction
&& ar->auxSwitchChannelIndex == arDefault->auxSwitchChannelIndex
&& ar->adjustmentIndex == arDefault->adjustmentIndex;
cliDumpPrintf(dumpMask, equalsDefault, "adjrange %u %u %u %u %u %u %u\r\n",
i,
@ -1525,8 +1525,8 @@ static void printRxRange(uint8_t dumpMask, master_t *defaultConfig)
for (int i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
channelRangeConfigurationDefault = &defaultConfig->rxConfig.channelRanges[i];
equalsDefault = channelRangeConfiguration->min == channelRangeConfigurationDefault->min
&& channelRangeConfiguration->max == channelRangeConfigurationDefault->max;
equalsDefault = channelRangeConfiguration->min == channelRangeConfigurationDefault->min
&& channelRangeConfiguration->max == channelRangeConfigurationDefault->max;
cliDumpPrintf(dumpMask, equalsDefault, "rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
}
}
@ -1619,8 +1619,8 @@ static void printColor(uint8_t dumpMask, master_t *defaultConfig)
color = &masterConfig.colors[i];
colorDefault = &defaultConfig->colors[i];
equalsDefault = color->h == colorDefault->h
&& color->s == colorDefault->s
&& color->v == colorDefault->v;
&& color->s == colorDefault->s
&& color->v == colorDefault->v;
cliDumpPrintf(dumpMask, equalsDefault, "color %u %d,%u,%u\r\n",
i,
color->h,
@ -2121,11 +2121,11 @@ static void printVtx(uint8_t dumpMask, master_t *defaultConfig)
for (int i = 0; i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; i++) {
cac = &masterConfig.vtxChannelActivationConditions[i];
cacDefault = &defaultConfig->vtxChannelActivationConditions[i];
equalsDefault = cac->auxChannelIndex == cacDefault->auxChannelIndex
equalsDefault = cac->auxChannelIndex == cacDefault->auxChannelIndex
&& cac->band == cacDefault->band
&& cac->channel == cacDefault->channel
&& cac->range.startStep == cacDefault->range.startStep
&& cac->range.endStep == cacDefault->range.endStep;
&& cac->channel == cacDefault->channel
&& cac->range.startStep == cacDefault->range.startStep
&& cac->range.endStep == cacDefault->range.endStep;
cliDumpPrintf(dumpMask, equalsDefault, "vtx %u %u %u %u %u %u\r\n",
i,
cac->auxChannelIndex,
@ -2246,7 +2246,7 @@ static bool valueEqualsDefault(const clivalue_t *value, master_t *defaultConfig)
case VAR_FLOAT:
result = *(float *)ptr == *(float *)ptrDefault;
break;
break;
}
return result;
}
@ -2378,11 +2378,11 @@ static void printConfig(char *cmdline, bool doDiff)
equalsDefault = masterConfig.customServoMixer[i].targetChannel == defaultConfig.customServoMixer[i].targetChannel
&& masterConfig.customServoMixer[i].inputSource == defaultConfig.customServoMixer[i].inputSource
&& masterConfig.customServoMixer[i].rate == defaultConfig.customServoMixer[i].rate
&& masterConfig.customServoMixer[i].speed == defaultConfig.customServoMixer[i].speed
&& masterConfig.customServoMixer[i].min == defaultConfig.customServoMixer[i].min
&& masterConfig.customServoMixer[i].max == defaultConfig.customServoMixer[i].max
&& masterConfig.customServoMixer[i].box == masterConfig.customServoMixer[i].box;
&& masterConfig.customServoMixer[i].rate == defaultConfig.customServoMixer[i].rate
&& masterConfig.customServoMixer[i].speed == defaultConfig.customServoMixer[i].speed
&& masterConfig.customServoMixer[i].min == defaultConfig.customServoMixer[i].min
&& masterConfig.customServoMixer[i].max == defaultConfig.customServoMixer[i].max
&& masterConfig.customServoMixer[i].box == masterConfig.customServoMixer[i].box;
cliDumpPrintf(dumpMask, equalsDefault,"smix %d %d %d %d %d %d %d %d\r\n",
i,
@ -2431,7 +2431,7 @@ static void printConfig(char *cmdline, bool doDiff)
equalsDefault = true;
for (i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++) {
buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
equalsDefault = equalsDefault && (masterConfig.rxConfig.rcmap[i] == defaultConfig.rxConfig.rcmap[i]);
equalsDefault = equalsDefault && (masterConfig.rxConfig.rcmap[i] == defaultConfig.rxConfig.rcmap[i]);
}
buf[i] = '\0';
cliDumpPrintf(dumpMask, equalsDefault, "map %s\r\n", buf);
@ -2483,8 +2483,9 @@ static void printConfig(char *cmdline, bool doDiff)
uint8_t currentRateIndex = currentProfile->activeRateProfile;
uint8_t rateCount;
for (rateCount=0; rateCount<MAX_RATEPROFILES; rateCount++)
for (rateCount = 0; rateCount < MAX_RATEPROFILES; rateCount++) {
cliDumpRateProfile(rateCount, dumpMask, &defaultConfig);
}
cliPrint("\r\n# restore original rateprofile selection\r\n");
changeControlRateProfile(currentRateIndex);
@ -2513,8 +2514,10 @@ static void printConfig(char *cmdline, bool doDiff)
static void cliDumpProfile(uint8_t profileIndex, uint8_t dumpMask, master_t *defaultConfig)
{
if (profileIndex >= MAX_PROFILE_COUNT) // Faulty values
if (profileIndex >= MAX_PROFILE_COUNT) {
// Faulty values
return;
}
changeProfile(profileIndex);
cliPrint("\r\n# profile\r\n");
cliProfile("");
@ -2525,8 +2528,10 @@ static void cliDumpProfile(uint8_t profileIndex, uint8_t dumpMask, master_t *def
static void cliDumpRateProfile(uint8_t rateProfileIndex, uint8_t dumpMask, master_t *defaultConfig)
{
if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values
if (rateProfileIndex >= MAX_RATEPROFILES) {
// Faulty values
return;
}
changeControlRateProfile(rateProfileIndex);
cliPrint("\r\n# rateprofile\r\n");
cliRateProfile("");
@ -2747,8 +2752,9 @@ static void cliMap(char *cmdline)
if (len == 8) {
// uppercase it
for (i = 0; i < 8; i++)
for (i = 0; i < 8; i++) {
cmdline[i] = toupper((unsigned char)cmdline[i]);
}
for (i = 0; i < 8; i++) {
if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
continue;
@ -2758,8 +2764,9 @@ static void cliMap(char *cmdline)
parseRcChannels(cmdline, &masterConfig.rxConfig);
}
cliPrint("Map: ");
for (i = 0; i < 8; i++)
for (i = 0; i < 8; i++) {
out[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
}
out[i] = '\0';
cliPrintf("%s\r\n", out);
}
@ -2955,12 +2962,9 @@ static void cliDefaults(char *cmdline)
static void cliPrint(const char *str)
{
while (*str)
while (*str) {
bufWriterAppend(cliWriter, *str++);
#ifdef USE_SLOW_SERIAL_CLI
delay(1);
#endif
}
}
static void cliPutp(void *p, char ch)
@ -2982,11 +2986,7 @@ static bool cliDumpPrintf(uint8_t dumpMask, bool equalsDefault, const char *form
tfp_format(cliWriter, cliPutp, format, va);
va_end(va);
#ifdef USE_SLOW_SERIAL_CLI
delay(1);
#endif
return true;
return true;
}
return false;
@ -2998,10 +2998,6 @@ static void cliPrintf(const char *fmt, ...)
va_start(va, fmt);
tfp_format(cliWriter, cliPutp, fmt, va);
va_end(va);
#ifdef USE_SLOW_SERIAL_CLI
delay(1);
#endif
}
static void cliWrite(uint8_t ch)
@ -3418,11 +3414,11 @@ void cliProcess(void)
cliBuffer[bufferIndex] = 0; // null terminate
const clicmd_t *cmd;
char *options;
char *options;
for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
if ((options = checkCommand(cliBuffer, cmd->name))) {
break;
}
}
}
if(cmd < cmdTable + CMD_COUNT)
cmd->func(options);

View file

@ -24,17 +24,16 @@
/* STM32F4 specific settings that apply to all F4 targets */
#ifdef STM32F4
#define MAX_AUX_CHANNELS 99
#define TASK_GYROPID_DESIRED_PERIOD 125
#define SCHEDULER_DELAY_LIMIT 10
#define USE_SLOW_SERIAL_CLI
#define I2C3_OVERCLOCK true
#define MAX_AUX_CHANNELS 99
#define TASK_GYROPID_DESIRED_PERIOD 125
#define SCHEDULER_DELAY_LIMIT 10
#define I2C3_OVERCLOCK true
#else /* when not an F4 */
#define MAX_AUX_CHANNELS 6
#define TASK_GYROPID_DESIRED_PERIOD 1000
#define SCHEDULER_DELAY_LIMIT 100
#define MAX_AUX_CHANNELS 6
#define TASK_GYROPID_DESIRED_PERIOD 1000
#define SCHEDULER_DELAY_LIMIT 100
#endif

View file

@ -305,6 +305,12 @@ uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength)
return sendLength;
}
uint32_t CDC_Send_FreeBytes(void)
{
/* this driver is blocking, so the buffer is unlimited */
return 255;
}
/*******************************************************************************
* Function Name : Receive DATA .
* Description : receive the data from the PC to STM32 and send it through USB
@ -338,6 +344,11 @@ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
return len;
}
uint32_t CDC_Receive_BytesAvailable(void)
{
return receiveLength;
}
/*******************************************************************************
* Function Name : usbIsConfigured.
* Description : Determines if USB VCP is configured or not

View file

@ -56,13 +56,15 @@ void USB_Interrupts_Config(void);
void USB_Cable_Config(FunctionalState NewState);
void Get_SerialNum(void);
uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength); // HJI
uint32_t CDC_Send_FreeBytes(void);
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len); // HJI
uint32_t CDC_Receive_BytesAvailable(void);
uint8_t usbIsConfigured(void); // HJI
uint8_t usbIsConnected(void); // HJI
uint32_t CDC_BaudRate(void);
/* External variables --------------------------------------------------------*/
extern __IO uint32_t receiveLength; // HJI
/* External variables --------------------------------------------------------*/
extern __IO uint32_t packetSent; // HJI
#endif /*__HW_CONFIG_H*/

View file

@ -39,12 +39,10 @@ __IO uint32_t bDeviceState = UNCONNECTED; /* USB device status */
/* This is the buffer for data received from the MCU to APP (i.e. MCU TX, APP RX) */
extern uint8_t APP_Rx_Buffer[];
extern uint32_t APP_Rx_ptr_out;
/* Increment this buffer position or roll it back to
start address when writing received data
in the buffer APP_Rx_Buffer. */
extern uint32_t APP_Rx_ptr_in;
__IO uint32_t receiveLength = 0;
/*
APP TX is the circular buffer for data that is transmitted from the APP (host)
@ -155,7 +153,7 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
/*******************************************************************************
* Function Name : Send DATA .
* Description : send the data received from the STM32 to the PC through USB
* Input : None.
* Input : buffer to send, and the length of the buffer.
* Output : None.
* Return : None.
*******************************************************************************/
@ -165,10 +163,21 @@ uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength)
return sendLength;
}
uint32_t CDC_Send_FreeBytes(void)
{
/*
return the bytes free in the circular buffer
functionally equivalent to:
(APP_Rx_ptr_out > APP_Rx_ptr_in ? APP_Rx_ptr_out - APP_Rx_ptr_in : APP_RX_DATA_SIZE - APP_Rx_ptr_in + APP_Rx_ptr_in)
but without the impact of the condition check.
*/
return ((APP_Rx_ptr_out - APP_Rx_ptr_in) + (-((int)(APP_Rx_ptr_out <= APP_Rx_ptr_in)) & APP_RX_DATA_SIZE)) - 1;
}
/**
* @brief VCP_DataTx
* CDC received data to be send over USB IN endpoint are managed in
* this function.
* CDC data to be sent to the Host (app) over USB
* @param Buf: Buffer of data to be sent
* @param Len: Number of data to be sent (in bytes)
* @retval Result of the operation: USBD_OK if all operations are OK else VCP_FAIL
@ -180,11 +189,13 @@ static uint16_t VCP_DataTx(uint8_t* Buf, uint32_t Len)
could just check for: USB_CDC_ZLP, but better to be safe
and wait for any existing transmission to complete.
*/
while (USB_Tx_State);
while (USB_Tx_State != 0);
for (uint32_t i = 0; i < Len; i++) {
APP_Rx_Buffer[APP_Rx_ptr_in] = Buf[i];
APP_Rx_ptr_in = (APP_Rx_ptr_in + 1) % APP_RX_DATA_SIZE;
while (CDC_Send_FreeBytes() <= 0);
}
return USBD_OK;
@ -205,16 +216,16 @@ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
recvBuf[count] = APP_Tx_Buffer[APP_Tx_ptr_out];
APP_Tx_ptr_out = (APP_Tx_ptr_out + 1) % APP_TX_DATA_SIZE;
count++;
receiveLength--;
}
if (!receiveLength) {
receiveLength = APP_Tx_ptr_out != APP_Tx_ptr_in;
}
return count;
}
uint32_t CDC_Receive_BytesAvailable(void)
{
/* return the bytes available in the receive circular buffer */
return APP_Tx_ptr_out > APP_Tx_ptr_in ? APP_TX_DATA_SIZE - APP_Tx_ptr_out + APP_Tx_ptr_in : APP_Tx_ptr_in - APP_Tx_ptr_out;
}
/**
* @brief VCP_DataRx
* Data received over USB OUT endpoint are sent over CDC interface
@ -232,9 +243,12 @@ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
*/
static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len)
{
if (CDC_Receive_BytesAvailable() + Len > APP_TX_DATA_SIZE) {
return USBD_FAIL;
}
__disable_irq();
receiveLength += Len;
for (uint32_t i = 0; i < Len; i++) {
APP_Tx_Buffer[APP_Tx_ptr_in] = Buf[i];
APP_Tx_ptr_in = (APP_Tx_ptr_in + 1) % APP_TX_DATA_SIZE;
@ -242,9 +256,6 @@ static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len)
__enable_irq();
if(receiveLength > APP_TX_DATA_SIZE)
return USBD_FAIL;
return USBD_OK;
}

View file

@ -37,14 +37,15 @@
__ALIGN_BEGIN USB_OTG_CORE_HANDLE USB_OTG_dev __ALIGN_END;
uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength); // HJI
uint32_t CDC_Send_FreeBytes(void);
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len); // HJI
uint32_t CDC_Receive_BytesAvailable(void);
uint8_t usbIsConfigured(void); // HJI
uint8_t usbIsConnected(void); // HJI
uint32_t CDC_BaudRate(void);
/* External variables --------------------------------------------------------*/
extern __IO uint32_t receiveLength; // HJI
extern __IO uint32_t bDeviceState; /* USB device status */
typedef enum _DEVICE_STATE {

View file

@ -177,33 +177,38 @@ uint32_t millis(void) {
uint32_t micros(void) { return 0; }
uint8_t serialRxBytesWaiting(serialPort_t *instance) {
uint32_t serialRxBytesWaiting(serialPort_t *instance)
{
UNUSED(instance);
return 0;
}
uint8_t serialTxBytesFree(serialPort_t *instance) {
uint32_t serialTxBytesFree(serialPort_t *instance)
{
UNUSED(instance);
return 0;
}
uint8_t serialRead(serialPort_t *instance) {
uint8_t serialRead(serialPort_t *instance)
{
UNUSED(instance);
return 0;
}
void serialWrite(serialPort_t *instance, uint8_t ch) {
void serialWrite(serialPort_t *instance, uint8_t ch)
{
UNUSED(instance);
UNUSED(ch);
}
void serialSetMode(serialPort_t *instance, portMode_t mode) {
void serialSetMode(serialPort_t *instance, portMode_t mode)
{
UNUSED(instance);
UNUSED(mode);
}
serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options) {
serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options)
{
UNUSED(identifier);
UNUSED(functionMask);
UNUSED(baudRate);
@ -214,30 +219,36 @@ serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFuncti
return NULL;
}
void closeSerialPort(serialPort_t *serialPort) {
void closeSerialPort(serialPort_t *serialPort)
{
UNUSED(serialPort);
}
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) {
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
{
UNUSED(function);
return NULL;
}
bool sensors(uint32_t mask) {
bool sensors(uint32_t mask)
{
UNUSED(mask);
return false;
}
bool telemetryDetermineEnabledState(portSharing_e) {
bool telemetryDetermineEnabledState(portSharing_e)
{
return true;
}
portSharing_e determinePortSharing(serialPortConfig_t *, serialPortFunction_e) {
portSharing_e determinePortSharing(serialPortConfig_t *, serialPortFunction_e)
{
return PORTSHARING_NOT_SHARED;
}
batteryState_e getBatteryState(void) {
batteryState_e getBatteryState(void)
{
return BATTERY_OK;
}