Merge branch 'master' into betaflight

Conflicts:
	src/main/blackbox/blackbox_io.c
	src/main/drivers/serial_usb_vcp.c
	src/main/flight/imu.c
	src/main/mw.c
	src/main/target/CC3D/target.h
This commit is contained in:
borisbstyle 2015-10-12 23:53:43 +02:00
commit 4b3ba927e9
50 changed files with 544 additions and 250 deletions

View File

@ -3,7 +3,6 @@ env:
- PUBLISHMETA=True
- PUBLISHDOCS=True
- TARGET=CC3D
- TARGET=CC3D OPBL=yes
- TARGET=COLIBRI_RACE
- TARGET=CHEBUZZF3
- TARGET=CJMCU

View File

@ -20,9 +20,6 @@ TARGET ?= NAZE
# Compile-time options
OPTIONS ?=
# compile for OpenPilot BootLoader support
OPBL ?=no
# Debugger optons, must be empty or GDB
DEBUG ?=
@ -40,9 +37,6 @@ FORKNAME = betaflight
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENWIIF1 ALIENWIIF3 COLIBRI_RACE MOTOLAB
# Valid targets for OP BootLoader support
OPBL_VALID_TARGETS = CC3D
# Configure default flash sizes for the targets
ifeq ($(FLASH_SIZE),)
ifeq ($(TARGET),$(filter $(TARGET),CJMCU))
@ -410,16 +404,6 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
$(HIGHEND_SRC) \
$(COMMON_SRC)
ifeq ($(OPBL),yes)
ifneq ($(filter $(TARGET),$(OPBL_VALID_TARGETS)),)
TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld
.DEFAULT_GOAL := binary
else
$(error OPBL specified with a unsupported target)
endif
endif
CJMCU_SRC = \
startup_stm32f10x_md_gcc.S \
drivers/adc.c \

View File

@ -98,9 +98,12 @@ save.
You need to let Cleanflight know which of [your serial ports][] you connect your OpenLog to (i.e. the Blackbox port),
which you can do on the Configurator's Ports tab.
A hardware serial port is required (such as UART1 on the Naze32, the two-pin Tx/Rx header in the center of the board).
SoftSerial ports cannot be used as they are too slow. Blackbox needs to be set to at least 115200 baud on this port.
When using fast looptimes (<2500), a baud rate of 250000 should be used instead in order to reduce dropped frames.
You should use a hardware serial port (such as UART1 on the Naze32, the two-pin Tx/Rx header in the center of the
board). SoftSerial ports can be used for the Blackbox. However, because they are limited to 19200 baud, your logging
rate will need to be severely reduced to compensate. Therefore the use of SoftSerial is not recommended.
When using a hardware serial port, Blackbox should be set to at least 115200 baud on that port. When using fast
looptimes (<2500), a baud rate of 250000 should be used instead in order to reduce dropped frames.
The serial port used for Blackbox cannot be shared with any other function (e.g. GPS, telemetry) except the MSP
protocol. If MSP is used on the same port as Blackbox, then MSP will be active when the board is disarmed, and Blackbox
@ -132,7 +135,7 @@ then you can use a spare motor header's +5V and GND pins to power the OpenLog wi
Boards other than the Naze32 may have more accessible hardware serial devices, in which case refer to their
documentation to decide how to wire up the logger. The key criteria are:
* Must be a hardware serial port. Not SoftSerial.
* Should be a hardware serial port rather than SoftSerial.
* Cannot be shared with any other function (GPS, telemetry) except MSP.
* If MSP is used on the same UART, MSP will stop working when the board is armed.
@ -214,6 +217,9 @@ set blackbox_rate_denom = 2
The data rate for my quadcopter using a looptime of 2400 and a rate of 1/1 is about 10.25kB/s. This allows about 18
days of flight logs to fit on my OpenLog's 16GB MicroSD card, which ought to be enough for anybody :).
If you are logging using SoftSerial, you will almost certainly need to reduce your logging rate to 1/32. Even at that
logging rate, looptimes faster than about 1000 cannot be successfully logged.
If you're logging to an onboard dataflash chip instead of an OpenLog, be aware that the 2MB of storage space it offers
is pretty small. At the default 1/1 logging rate, and a 2400 looptime, this is only enough for about 3 minutes of
flight. This could be long enough for you to investigate some flying problem with your craft, but you may want to reduce

View File

@ -120,7 +120,7 @@ Custom servo mixing rules can be applied to each servo. Rules are applied in th
| 2 | Stabilised YAW |
| 3 | Stabilised THROTTLE |
| 4 | RC ROLL |
| 5 | RC ITCH |
| 5 | RC PITCH |
| 6 | RC YAW |
| 7 | RC THROTTLE |
| 8 | RC AUX 1 |
@ -205,3 +205,63 @@ profile 2
smix reverse 5 2 r
```
### Example 4: Custom Airplane for 6 Pinout Boards like [Afromini Amaze rev3 (Mini Naze32)](http://abusemark.com/store/index.php?main_page=product_info&cPath=1&products_id=45)
Here is an example of a custom single engine plane.
Servo control has been moved from pins 3,4,5,6 to 2,3,4,5 to acomidate only 6 pinouts.
| Pins | Outputs |
|------|------------------|
| 1 | Main Motor |
| 2 | [EMPTY] |
| 3 | Roll / Aileron |
| 4 | Roll / Aileron |
| 5 | Yaw / Rudder |
| 6 | Pitch / Elevator |
```
mixer CUSTOMAIRPLANE
mmix reset
mmix 0 1.0 0.0 0.0 0.0 # Engine
smix reset
# Rule Servo Source Rate Speed Min Max Box
smix 0 2 0 100 0 0 100 0 # Roll / Aileron
smix 1 3 0 100 0 0 100 0 # Roll / Aileron
smix 3 4 2 100 0 0 100 0 # Yaw / Rudder
smix 2 5 1 100 0 0 100 0 # Pitch / Elevator
```
### Example 5: Custom Airplane with Differential Thrust
Here is an example of a custom twin engine plane with [Differential Thrust](http://rcvehicles.about.com/od/rcairplanes/ss/RCAirplaneBasic.htm#step8)
Motors take the first 2 pins, the servos take pins as indicated in the [Servo slot] chart above.
Settings bellow have motor yaw influence at "0.3", you can change this nuber to have more or less differential thrust over the two motors.
Note: You can look at the Motors tab in [Cleanflight Cofigurator](https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en) to see motor and servo outputs.
| Pins | Outputs |
|------|------------------|
| 1 | Left Engine |
| 2 | Right Engine |
| 3 | [EMPTY] |
| 4 | Roll / Aileron |
| 5 | Roll / Aileron |
| 6 | Yaw / Rudder |
| 7 | Pitch / Elevator |
| 8 | [EMPTY] |
```
mixer CUSTOMAIRPLANE
mmix reset
mmix 0 1.0 0.0 0.0 0.3 # Left Engine
mmix 1 1.0 0.0 0.0 -0.3 # Right Engine
smix reset
# Rule Servo Source Rate Speed Min Max Box
smix 0 3 0 100 0 0 100 0 # Roll / Aileron
smix 1 4 0 100 0 0 100 0 # Roll / Aileron
smix 3 5 2 100 0 0 100 0 # Yaw / Rudder
smix 2 6 1 100 0 0 100 0 # Pitch / Elevator
```

View File

@ -39,8 +39,6 @@ Current meter cannot be used in conjunction with Sonar.
| ------------- | ------------- | ------------------- |
| PB5 | PB0 | YES (3.3v input) |
Sonar support is not available when using the OpenPilot bootloader (OPBL).
#### Constraints
Sonar cannot be used in conjuction with SoftSerial or Parallel PWM.

View File

@ -105,9 +105,3 @@ git pull
make clean TARGET=NAZE
make TARGET=NAZE
```
Or in the case of CC3D in need of a `obj/cleanflight_CC3D.bin`
```
make clean TARGET=CC3D
make TARGET=CC3D OPBL=yes
```

View File

@ -3,7 +3,6 @@
targets=("PUBLISHMETA=True" \
"RUNTESTS=True" \
"TARGET=CC3D" \
"TARGET=CC3D OPBL=yes" \
"TARGET=CHEBUZZF3" \
"TARGET=CJMCU" \
"TARGET=COLIBRI_RACE" \
@ -26,7 +25,7 @@ export TRAVIS_REPO_SLUG=${TRAVIS_REPO_SLUG:=$USER/simulated}
for target in "${targets[@]}"
do
unset RUNTESTS PUBLISHMETA TARGET OPBL
unset RUNTESTS PUBLISHMETA TARGET
eval "export $target"
make clean
./.travis.sh

View File

@ -111,7 +111,7 @@ static const char* const blackboxFieldHeaderNames[] = {
};
/* All field definition structs should look like this (but with longer arrs): */
typedef struct blackboxFieldDefinition_t {
typedef struct blackboxFieldDefinition_s {
const char *name;
// If the field name has a number to be included in square brackets [1] afterwards, set it here, or -1 for no brackets:
int8_t fieldNameIndex;
@ -124,7 +124,7 @@ typedef struct blackboxFieldDefinition_t {
#define BLACKBOX_SIMPLE_FIELD_HEADER_COUNT (BLACKBOX_DELTA_FIELD_HEADER_COUNT - 2)
#define BLACKBOX_CONDITIONAL_FIELD_HEADER_COUNT (BLACKBOX_DELTA_FIELD_HEADER_COUNT - 2)
typedef struct blackboxSimpleFieldDefinition_t {
typedef struct blackboxSimpleFieldDefinition_s {
const char *name;
int8_t fieldNameIndex;
@ -133,7 +133,7 @@ typedef struct blackboxSimpleFieldDefinition_t {
uint8_t encode;
} blackboxSimpleFieldDefinition_t;
typedef struct blackboxConditionalFieldDefinition_t {
typedef struct blackboxConditionalFieldDefinition_s {
const char *name;
int8_t fieldNameIndex;
@ -143,7 +143,7 @@ typedef struct blackboxConditionalFieldDefinition_t {
uint8_t condition; // Decide whether this field should appear in the log
} blackboxConditionalFieldDefinition_t;
typedef struct blackboxDeltaFieldDefinition_t {
typedef struct blackboxDeltaFieldDefinition_s {
const char *name;
int8_t fieldNameIndex;
@ -264,7 +264,10 @@ typedef enum BlackboxState {
BLACKBOX_STATE_SHUTTING_DOWN
} BlackboxState;
typedef struct blackboxMainState_t {
#define BLACKBOX_FIRST_HEADER_SENDING_STATE BLACKBOX_STATE_SEND_HEADER
#define BLACKBOX_LAST_HEADER_SENDING_STATE BLACKBOX_STATE_SEND_SYSINFO
typedef struct blackboxMainState_s {
uint32_t time;
int32_t axisPID_P[XYZ_AXIS_COUNT], axisPID_I[XYZ_AXIS_COUNT], axisPID_D[XYZ_AXIS_COUNT];
@ -290,13 +293,13 @@ typedef struct blackboxMainState_t {
uint16_t rssi;
} blackboxMainState_t;
typedef struct blackboxGpsState_t {
typedef struct blackboxGpsState_s {
int32_t GPS_home[2], GPS_coord[2];
uint8_t GPS_numSat;
} blackboxGpsState_t;
// This data is updated really infrequently:
typedef struct blackboxSlowState_t {
typedef struct blackboxSlowState_s {
uint16_t flightModeFlags;
uint8_t stateFlags;
uint8_t failsafePhase;
@ -325,7 +328,6 @@ static struct {
*/
union {
int fieldIndex;
int serialBudget;
uint32_t startTime;
} u;
} xmitState;
@ -452,6 +454,7 @@ static void blackboxSetState(BlackboxState newState)
//Perform initial setup required for the new state
switch (newState) {
case BLACKBOX_STATE_SEND_HEADER:
blackboxHeaderBudget = 0;
xmitState.headerIndex = 0;
xmitState.u.startTime = millis();
break;
@ -973,7 +976,6 @@ static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const v
const void *secondFieldDefinition, int fieldCount, const uint8_t *conditions, const uint8_t *secondCondition)
{
const blackboxFieldDefinition_t *def;
int charsWritten;
unsigned int headerCount;
static bool needComma = false;
size_t definitionStride = (char*) secondFieldDefinition - (char*) fieldDefinitions;
@ -989,46 +991,76 @@ static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const v
* We're chunking up the header data so we don't exceed our datarate. So we'll be called multiple times to transmit
* the whole header.
*/
// On our first call we need to print the name of the header and a colon
if (xmitState.u.fieldIndex == -1) {
if (xmitState.headerIndex >= headerCount) {
return false; //Someone probably called us again after we had already completed transmission
}
charsWritten = blackboxPrintf("H Field %c %s:", xmitState.headerIndex >= BLACKBOX_SIMPLE_FIELD_HEADER_COUNT ? deltaFrameChar : mainFrameChar, blackboxFieldHeaderNames[xmitState.headerIndex]);
uint32_t charsToBeWritten = strlen("H Field x :") + strlen(blackboxFieldHeaderNames[xmitState.headerIndex]);
if (blackboxDeviceReserveBufferSpace(charsToBeWritten) != BLACKBOX_RESERVE_SUCCESS) {
return true; // Try again later
}
blackboxHeaderBudget -= blackboxPrintf("H Field %c %s:", xmitState.headerIndex >= BLACKBOX_SIMPLE_FIELD_HEADER_COUNT ? deltaFrameChar : mainFrameChar, blackboxFieldHeaderNames[xmitState.headerIndex]);
xmitState.u.fieldIndex++;
needComma = false;
} else
charsWritten = 0;
}
for (; xmitState.u.fieldIndex < fieldCount && charsWritten < blackboxWriteChunkSize; xmitState.u.fieldIndex++) {
// The longest we expect an integer to be as a string:
const uint32_t LONGEST_INTEGER_STRLEN = 2;
for (; xmitState.u.fieldIndex < fieldCount; xmitState.u.fieldIndex++) {
def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * xmitState.u.fieldIndex);
if (!conditions || testBlackboxCondition(conditions[conditionsStride * xmitState.u.fieldIndex])) {
// First (over)estimate the length of the string we want to print
int32_t bytesToWrite = 1; // Leading comma
// The first header is a field name
if (xmitState.headerIndex == 0) {
bytesToWrite += strlen(def->name) + strlen("[]") + LONGEST_INTEGER_STRLEN;
} else {
//The other headers are integers
bytesToWrite += LONGEST_INTEGER_STRLEN;
}
// Now perform the write if the buffer is large enough
if (blackboxDeviceReserveBufferSpace(bytesToWrite) != BLACKBOX_RESERVE_SUCCESS) {
// Ran out of space!
return true;
}
blackboxHeaderBudget -= bytesToWrite;
if (needComma) {
blackboxWrite(',');
charsWritten++;
} else {
needComma = true;
}
// The first header is a field name
if (xmitState.headerIndex == 0) {
charsWritten += blackboxPrint(def->name);
blackboxPrint(def->name);
// Do we need to print an index in brackets after the name?
if (def->fieldNameIndex != -1) {
charsWritten += blackboxPrintf("[%d]", def->fieldNameIndex);
blackboxPrintf("[%d]", def->fieldNameIndex);
}
} else {
//The other headers are integers
charsWritten += blackboxPrintf("%d", def->arr[xmitState.headerIndex - 1]);
blackboxPrintf("%d", def->arr[xmitState.headerIndex - 1]);
}
}
}
// Did we complete this line?
if (xmitState.u.fieldIndex == fieldCount) {
if (xmitState.u.fieldIndex == fieldCount && blackboxDeviceReserveBufferSpace(1) == BLACKBOX_RESERVE_SUCCESS) {
blackboxHeaderBudget--;
blackboxWrite('\n');
xmitState.headerIndex++;
xmitState.u.fieldIndex = -1;
@ -1043,68 +1075,57 @@ static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const v
*/
static bool blackboxWriteSysinfo()
{
if (xmitState.headerIndex == 0) {
xmitState.u.serialBudget = 0;
xmitState.headerIndex = 1;
}
// How many bytes can we afford to transmit this loop?
xmitState.u.serialBudget = MIN(xmitState.u.serialBudget + blackboxWriteChunkSize, 64);
// Most headers will consume at least 20 bytes so wait until we've built up that much link budget
if (xmitState.u.serialBudget < 20) {
// Make sure we have enough room in the buffer for our longest line (as of this writing, the "Firmware date" line)
if (blackboxDeviceReserveBufferSpace(64) != BLACKBOX_RESERVE_SUCCESS) {
return false;
}
switch (xmitState.headerIndex) {
case 0:
//Shouldn't ever get here
blackboxPrintfHeaderLine("Firmware type:Cleanflight");
break;
case 1:
xmitState.u.serialBudget -= blackboxPrint("H Firmware type:Cleanflight\n");
blackboxPrintfHeaderLine("Firmware revision:%s", shortGitRevision);
break;
case 2:
xmitState.u.serialBudget -= blackboxPrintf("H Firmware revision:%s\n", shortGitRevision);
blackboxPrintfHeaderLine("Firmware date:%s %s", buildDate, buildTime);
break;
case 3:
xmitState.u.serialBudget -= blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime);
blackboxPrintfHeaderLine("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
break;
case 4:
xmitState.u.serialBudget -= blackboxPrintf("H P interval:%d/%d\n", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
blackboxPrintfHeaderLine("rcRate:%d", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
break;
case 5:
xmitState.u.serialBudget -= blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
blackboxPrintfHeaderLine("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle);
break;
case 6:
xmitState.u.serialBudget -= blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle);
blackboxPrintfHeaderLine("maxthrottle:%d", masterConfig.escAndServoConfig.maxthrottle);
break;
case 7:
xmitState.u.serialBudget -= blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle);
blackboxPrintfHeaderLine("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale));
break;
case 8:
xmitState.u.serialBudget -= blackboxPrintf("H gyro.scale:0x%x\n", castFloatBytesToInt(gyro.scale));
blackboxPrintfHeaderLine("acc_1G:%u", acc_1G);
break;
case 9:
xmitState.u.serialBudget -= blackboxPrintf("H acc_1G:%u\n", acc_1G);
break;
case 10:
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
xmitState.u.serialBudget -= blackboxPrintf("H vbatscale:%u\n", masterConfig.batteryConfig.vbatscale);
blackboxPrintfHeaderLine("vbatscale:%u", masterConfig.batteryConfig.vbatscale);
} else {
xmitState.headerIndex += 2; // Skip the next two vbat fields too
}
break;
case 11:
xmitState.u.serialBudget -= blackboxPrintf("H vbatcellvoltage:%u,%u,%u\n", masterConfig.batteryConfig.vbatmincellvoltage,
case 10:
blackboxPrintfHeaderLine("vbatcellvoltage:%u,%u,%u", masterConfig.batteryConfig.vbatmincellvoltage,
masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage);
break;
case 12:
xmitState.u.serialBudget -= blackboxPrintf("H vbatref:%u\n", vbatReference);
case 11:
blackboxPrintfHeaderLine("vbatref:%u", vbatReference);
break;
case 13:
case 12:
//Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too:
if (feature(FEATURE_CURRENT_METER)) {
xmitState.u.serialBudget -= blackboxPrintf("H currentMeter:%d,%d\n", masterConfig.batteryConfig.currentMeterOffset, masterConfig.batteryConfig.currentMeterScale);
blackboxPrintfHeaderLine("currentMeter:%d,%d", masterConfig.batteryConfig.currentMeterOffset, masterConfig.batteryConfig.currentMeterScale);
}
break;
default:
@ -1262,21 +1283,28 @@ void handleBlackbox(void)
{
int i;
if (blackboxState >= BLACKBOX_FIRST_HEADER_SENDING_STATE && blackboxState <= BLACKBOX_LAST_HEADER_SENDING_STATE) {
blackboxReplenishHeaderBudget();
}
switch (blackboxState) {
case BLACKBOX_STATE_SEND_HEADER:
//On entry of this state, xmitState.headerIndex is 0 and startTime is intialised
/*
* Once the UART has had time to init, transmit the header in chunks so we don't overflow our transmit
* buffer.
* Once the UART has had time to init, transmit the header in chunks so we don't overflow its transmit
* buffer, overflow the OpenLog's buffer, or keep the main loop busy for too long.
*/
if (millis() > xmitState.u.startTime + 100) {
for (i = 0; i < blackboxWriteChunkSize && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++) {
blackboxWrite(blackboxHeader[xmitState.headerIndex]);
}
if (blackboxDeviceReserveBufferSpace(BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION) == BLACKBOX_RESERVE_SUCCESS) {
for (i = 0; i < BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++) {
blackboxWrite(blackboxHeader[xmitState.headerIndex]);
blackboxHeaderBudget--;
}
if (blackboxHeader[xmitState.headerIndex] == '\0') {
blackboxSetState(BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER);
if (blackboxHeader[xmitState.headerIndex] == '\0') {
blackboxSetState(BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER);
}
}
}
break;

View File

@ -109,40 +109,38 @@ typedef enum FlightLogEvent {
FLIGHT_LOG_EVENT_LOG_END = 255
} FlightLogEvent;
typedef struct flightLogEvent_syncBeep_t {
typedef struct flightLogEvent_syncBeep_s {
uint32_t time;
} flightLogEvent_syncBeep_t;
typedef struct flightLogEvent_inflightAdjustment_t {
typedef struct flightLogEvent_inflightAdjustment_s {
uint8_t adjustmentFunction;
bool floatFlag;
int32_t newValue;
float newFloatValue;
} flightLogEvent_inflightAdjustment_t;
typedef struct flightLogEvent_loggingResume_t {
typedef struct flightLogEvent_loggingResume_s {
uint32_t logIteration;
uint32_t currentTime;
} flightLogEvent_loggingResume_t;
#define FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT_FUNCTION_FLOAT_VALUE_FLAG 128
typedef struct flightLogEvent_gtuneCycleResult_t {
typedef struct flightLogEvent_gtuneCycleResult_s {
uint8_t gtuneAxis;
int32_t gtuneGyroAVG;
int16_t gtuneNewP;
} flightLogEvent_gtuneCycleResult_t;
typedef union flightLogEventData_t
{
typedef union flightLogEventData_u {
flightLogEvent_syncBeep_t syncBeep;
flightLogEvent_inflightAdjustment_t inflightAdjustment;
flightLogEvent_loggingResume_t loggingResume;
flightLogEvent_gtuneCycleResult_t gtuneCycleResult;
} flightLogEventData_t;
typedef struct flightLogEvent_t
{
typedef struct flightLogEvent_s {
FlightLogEvent event;
flightLogEventData_t data;
} flightLogEvent_t;

View File

@ -65,13 +65,15 @@
#define BLACKBOX_SERIAL_PORT_MODE MODE_TX
// How many bytes should we transmit per loop iteration?
uint8_t blackboxWriteChunkSize = 16;
// How many bytes can we transmit per loop iteration when writing headers?
static uint8_t blackboxMaxHeaderBytesPerIteration;
// How many bytes can we write *this* iteration without overflowing transmit buffers or overstressing the OpenLog?
int32_t blackboxHeaderBudget;
static serialPort_t *blackboxPort = NULL;
static portSharing_e blackboxPortSharing;
void blackboxWrite(uint8_t value)
{
switch (masterConfig.blackbox_device) {
@ -93,17 +95,49 @@ static void _putc(void *p, char c)
blackboxWrite(c);
}
static int blackboxPrintfv(const char *fmt, va_list va)
{
return tfp_format(NULL, _putc, fmt, va);
}
//printf() to the blackbox serial port with no blocking shenanigans (so it's caller's responsibility to not write too fast!)
int blackboxPrintf(const char *fmt, ...)
{
va_list va;
va_start(va, fmt);
int written = tfp_format(NULL, _putc, fmt, va);
int written = blackboxPrintfv(fmt, va);
va_end(va);
return written;
}
// Print the null-terminated string 's' to the serial port and return the number of bytes written
/*
* printf a Blackbox header line with a leading "H " and trailing "\n" added automatically. blackboxHeaderBudget is
* decreased to account for the number of bytes written.
*/
void blackboxPrintfHeaderLine(const char *fmt, ...)
{
va_list va;
blackboxWrite('H');
blackboxWrite(' ');
va_start(va, fmt);
int written = blackboxPrintfv(fmt, va);
va_end(va);
blackboxWrite('\n');
blackboxHeaderBudget -= written + 3;
}
// Print the null-terminated string 's' to the blackbox device and return the number of bytes written
int blackboxPrint(const char *s)
{
int length;
@ -464,15 +498,6 @@ bool blackboxDeviceFlush(void)
*/
bool blackboxDeviceOpen(void)
{
/*
* We want to write at about 7200 bytes per second to give the OpenLog a good chance to save to disk. If
* about looptime microseconds elapse between our writes, this is the budget of how many bytes we should
* transmit with each write.
*
* 9 / 1250 = 7200 / 1000000
*/
blackboxWriteChunkSize = MAX((targetLooptime * 9) / 1250, 4);
switch (masterConfig.blackbox_device) {
case BLACKBOX_DEVICE_SERIAL:
{
@ -500,6 +525,18 @@ bool blackboxDeviceOpen(void)
blackboxPort = openSerialPort(portConfig->identifier, FUNCTION_BLACKBOX, NULL, baudRates[baudRateIndex],
BLACKBOX_SERIAL_PORT_MODE, portOptions);
/*
* The slowest MicroSD cards have a write latency approaching 150ms. The OpenLog's buffer is about 900
* bytes. In order for its buffer to be able to absorb this latency we must write slower than 6000 B/s.
*
* So:
* Bytes per loop iteration = floor((looptime_ns / 1000000.0) * 6000)
* = floor((looptime_ns * 6000) / 1000000.0)
* = floor((looptime_ns * 3) / 500.0)
* = (looptime_ns * 3) / 500
*/
blackboxMaxHeaderBytesPerIteration = constrain((targetLooptime * 3) / 500, 1, BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION);
return blackboxPort != NULL;
}
break;
@ -509,6 +546,8 @@ bool blackboxDeviceOpen(void)
return false;
}
blackboxMaxHeaderBytesPerIteration = BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION;
return true;
break;
#endif
@ -559,4 +598,88 @@ bool isBlackboxDeviceFull(void)
}
}
/**
* Call once every loop iteration in order to maintain the global blackboxHeaderBudget with the number of bytes we can
* transmit this iteration.
*/
void blackboxReplenishHeaderBudget()
{
int32_t freeSpace;
switch (masterConfig.blackbox_device) {
case BLACKBOX_DEVICE_SERIAL:
freeSpace = serialTxBytesFree(blackboxPort);
break;
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
freeSpace = flashfsGetWriteBufferFreeSpace();
break;
#endif
default:
freeSpace = 0;
}
blackboxHeaderBudget = MIN(MIN(freeSpace, blackboxHeaderBudget + blackboxMaxHeaderBytesPerIteration), BLACKBOX_MAX_ACCUMULATED_HEADER_BUDGET);
}
/**
* You must call this function before attempting to write Blackbox header bytes to ensure that the write will not
* cause buffers to overflow. The number of bytes you can write is capped by the blackboxHeaderBudget. Calling this
* reservation function doesn't decrease blackboxHeaderBudget, so you must manually decrement that variable by the
* number of bytes you actually wrote.
*
* When the Blackbox device is FlashFS, a successful return code guarantees that no data will be lost if you write that
* many bytes to the device (i.e. FlashFS's buffers won't overflow).
*
* When the device is a serial port, a successful return code guarantees that Cleanflight's serial Tx buffer will not
* overflow, and the outgoing bandwidth is likely to be small enough to give the OpenLog time to absorb MicroSD card
* latency. However the OpenLog could still end up silently dropping data.
*
* Returns:
* BLACKBOX_RESERVE_SUCCESS - Upon success
* BLACKBOX_RESERVE_TEMPORARY_FAILURE - The buffer is currently too full to service the request, try again later
* BLACKBOX_RESERVE_PERMANENT_FAILURE - The buffer is too small to ever service this request
*/
blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes)
{
if (bytes <= blackboxHeaderBudget) {
return BLACKBOX_RESERVE_SUCCESS;
}
// Handle failure:
switch (masterConfig.blackbox_device) {
case BLACKBOX_DEVICE_SERIAL:
/*
* One byte of the tx buffer isn't available for user data (due to its circular list implementation),
* hence the -1. Note that the USB VCP implementation doesn't use a buffer and has txBufferSize set to zero.
*/
if (blackboxPort->txBufferSize && bytes > (int32_t) blackboxPort->txBufferSize - 1) {
return BLACKBOX_RESERVE_PERMANENT_FAILURE;
}
return BLACKBOX_RESERVE_TEMPORARY_FAILURE;
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
if (bytes > (int32_t) flashfsGetWriteBufferSize()) {
return BLACKBOX_RESERVE_PERMANENT_FAILURE;
}
if (bytes > (int32_t) flashfsGetWriteBufferFreeSpace()) {
/*
* The write doesn't currently fit in the buffer, so try to make room for it. Our flushing here means
* that the Blackbox header writing code doesn't have to guess about the best time to ask flashfs to
* flush, and doesn't stall waiting for a flush that would otherwise not automatically be called.
*/
flashfsFlushAsync();
}
return BLACKBOX_RESERVE_TEMPORARY_FAILURE;
#endif
default:
return BLACKBOX_RESERVE_PERMANENT_FAILURE;
}
}
#endif

View File

@ -32,11 +32,30 @@ typedef enum BlackboxDevice {
BLACKBOX_DEVICE_END
} BlackboxDevice;
extern uint8_t blackboxWriteChunkSize;
typedef enum {
BLACKBOX_RESERVE_SUCCESS,
BLACKBOX_RESERVE_TEMPORARY_FAILURE,
BLACKBOX_RESERVE_PERMANENT_FAILURE
} blackboxBufferReserveStatus_e;
/*
* We want to limit how bursty our writes to the device are. Note that this will also restrict the maximum size of a
* header write we can make:
*/
#define BLACKBOX_MAX_ACCUMULATED_HEADER_BUDGET 256
/*
* Ideally, each iteration in which we are logging headers would write a similar amount of data to the device as a
* regular logging iteration. This way we won't hog the CPU by making a gigantic write:
*/
#define BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION 64
extern int32_t blackboxHeaderBudget;
void blackboxWrite(uint8_t value);
int blackboxPrintf(const char *fmt, ...);
void blackboxPrintfHeaderLine(const char *fmt, ...);
int blackboxPrint(const char *s);
void blackboxWriteUnsignedVB(uint32_t value);
@ -55,3 +74,6 @@ bool blackboxDeviceOpen(void);
void blackboxDeviceClose(void);
bool isBlackboxDeviceFull(void);
void blackboxReplenishHeaderBudget();
blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes);

View File

@ -34,7 +34,7 @@
#define MAX(a, b) ((a) > (b) ? (a) : (b))
#define ABS(x) ((x) > 0 ? (x) : -(x))
typedef struct stdev_t
typedef struct stdev_s
{
float m_oldM, m_newM, m_oldS, m_newS;
int m_n;

View File

@ -42,9 +42,11 @@ http://resnet.uoregon.edu/~gurney_j/jmpc/bitwise.html
#else
// non ISO variant from linux kernel; checks ptr type, but triggers 'ISO C forbids braced-groups within expressions [-Wpedantic]'
// __extension__ is here to disable this warning
#define container_of(ptr, type, member) __extension__ ({ \
#define container_of(ptr, type, member) ( __extension__ ({ \
const typeof( ((type *)0)->member ) *__mptr = (ptr); \
(type *)( (char *)__mptr - offsetof(type,member) );})
(type *)( (char *)__mptr - offsetof(type,member) );}))
static inline int16_t cmp16(uint16_t a, uint16_t b) { return a-b; }
static inline int32_t cmp32(uint32_t a, uint32_t b) { return a-b; }
#endif

View File

@ -17,7 +17,7 @@
#pragma once
typedef struct drv_adxl345_config_t {
typedef struct drv_adxl345_config_s {
bool useFifo;
uint16_t dataRate;
} drv_adxl345_config_t;

View File

@ -27,14 +27,14 @@ typedef enum {
#define ADC_CHANNEL_COUNT (ADC_CHANNEL_MAX + 1)
typedef struct adc_config_t {
typedef struct adc_config_s {
uint8_t adcChannel; // ADC1_INxx channel number
uint8_t dmaIndex; // index into DMA buffer in case of sparse channels
bool enabled;
uint8_t sampleTime;
} adc_config_t;
typedef struct drv_adc_config_t {
typedef struct drv_adc_config_s {
bool enableVBat;
bool enableRSSI;
bool enableCurrentMeter;

View File

@ -33,6 +33,13 @@
#include "adc.h"
#include "adc_impl.h"
#ifndef ADC_INSTANCE
#define ADC_INSTANCE ADC1
#define ADC_ABP2_PERIPHERAL RCC_APB2Periph_ADC1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
#define ADC_DMA_CHANNEL DMA1_Channel1
#endif
// Driver for STM32F103CB onboard ADC
//
// Naze32
@ -50,15 +57,13 @@ void adcInit(drv_adc_config_t *init)
UNUSED(init);
#endif
ADC_InitTypeDef adc;
DMA_InitTypeDef dma;
GPIO_InitTypeDef GPIO_InitStructure;
uint8_t i;
uint8_t configuredAdcChannels = 0;
memset(&adcConfig, 0, sizeof(adcConfig));
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
@ -107,50 +112,53 @@ void adcInit(drv_adc_config_t *init)
#endif
RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI)
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);
RCC_AHBPeriphClockCmd(ADC_AHB_PERIPHERAL, ENABLE);
RCC_APB2PeriphClockCmd(ADC_ABP2_PERIPHERAL, ENABLE);
// FIXME ADC driver assumes all the GPIO was already placed in 'AIN' mode
DMA_DeInit(DMA1_Channel1);
dma.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR;
dma.DMA_MemoryBaseAddr = (uint32_t)adcValues;
dma.DMA_DIR = DMA_DIR_PeripheralSRC;
dma.DMA_BufferSize = configuredAdcChannels;
dma.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
dma.DMA_MemoryInc = configuredAdcChannels > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable;
dma.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
dma.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
dma.DMA_Mode = DMA_Mode_Circular;
dma.DMA_Priority = DMA_Priority_High;
dma.DMA_M2M = DMA_M2M_Disable;
DMA_Init(DMA1_Channel1, &dma);
DMA_Cmd(DMA1_Channel1, ENABLE);
DMA_DeInit(ADC_DMA_CHANNEL);
DMA_InitTypeDef DMA_InitStructure;
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC_INSTANCE->DR;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
DMA_InitStructure.DMA_BufferSize = configuredAdcChannels;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_MemoryInc = configuredAdcChannels > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_Init(ADC_DMA_CHANNEL, &DMA_InitStructure);
DMA_Cmd(ADC_DMA_CHANNEL, ENABLE);
adc.ADC_Mode = ADC_Mode_Independent;
adc.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE;
adc.ADC_ContinuousConvMode = ENABLE;
adc.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
adc.ADC_DataAlign = ADC_DataAlign_Right;
adc.ADC_NbrOfChannel = configuredAdcChannels;
ADC_Init(ADC1, &adc);
ADC_InitTypeDef ADC_InitStructure;
ADC_StructInit(&ADC_InitStructure);
ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE;
ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
ADC_InitStructure.ADC_NbrOfChannel = configuredAdcChannels;
ADC_Init(ADC_INSTANCE, &ADC_InitStructure);
uint8_t rank = 1;
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].enabled) {
continue;
}
ADC_RegularChannelConfig(ADC1, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
ADC_RegularChannelConfig(ADC_INSTANCE, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
}
ADC_DMACmd(ADC1, ENABLE);
ADC_Cmd(ADC1, ENABLE);
ADC_DMACmd(ADC_INSTANCE, ENABLE);
ADC_Cmd(ADC_INSTANCE, ENABLE);
ADC_ResetCalibration(ADC1);
while(ADC_GetResetCalibrationStatus(ADC1));
ADC_StartCalibration(ADC1);
while(ADC_GetCalibrationStatus(ADC1));
ADC_ResetCalibration(ADC_INSTANCE);
while(ADC_GetResetCalibrationStatus(ADC_INSTANCE));
ADC_StartCalibration(ADC_INSTANCE);
while(ADC_GetCalibrationStatus(ADC_INSTANCE));
ADC_SoftwareStartConvCmd(ADC1, ENABLE);
ADC_SoftwareStartConvCmd(ADC_INSTANCE, ENABLE);
}

View File

@ -20,7 +20,7 @@
typedef void (*baroOpFuncPtr)(void); // baro start operation
typedef void (*baroCalculateFuncPtr)(int32_t *pressure, int32_t *temperature); // baro calculation (filled params are pressure and temperature)
typedef struct baro_t {
typedef struct baro_s {
uint16_t ut_delay;
uint16_t up_delay;
baroOpFuncPtr start_ut;

View File

@ -72,7 +72,7 @@
#define T_SETUP_PRESSURE_MAX (10)
// 10/16 = 0.625 ms
typedef struct bmp280_calib_param_t {
typedef struct bmp280_calib_param_s {
uint16_t dig_T1; /* calibration T1 data */
int16_t dig_T2; /* calibration T2 data */
int16_t dig_T3; /* calibration T3 data */

View File

@ -44,7 +44,7 @@ static void i2c_er_handler(void);
static void i2c_ev_handler(void);
static void i2cUnstick(void);
typedef struct i2cDevice_t {
typedef struct i2cDevice_s {
I2C_TypeDef *dev;
GPIO_TypeDef *gpio;
uint16_t scl;

View File

@ -19,7 +19,7 @@
#include <stdint.h>
typedef struct flashGeometry_t {
typedef struct flashGeometry_s {
uint16_t sectors; // Count of the number of erasable blocks on the device
uint16_t pagesPerSector;

View File

@ -44,7 +44,7 @@ typedef struct sonarGPIOConfig_s {
uint16_t echoPin;
} sonarGPIOConfig_t;
typedef struct drv_pwm_config_t {
typedef struct drv_pwm_config_s {
bool useParallelPWM;
bool usePPM;
bool useSerialRx;

View File

@ -83,7 +83,7 @@ static uint8_t ppmFrameCount = 0;
static uint8_t lastPPMFrameCount = 0;
static uint8_t ppmCountShift = 0;
typedef struct ppmDevice {
typedef struct ppmDevice_s {
uint8_t pulseIndex;
uint32_t previousTime;
uint32_t currentTime;

View File

@ -40,9 +40,14 @@ void serialWrite(serialPort_t *instance, uint8_t ch)
instance->vTable->serialWrite(instance, ch);
}
uint8_t serialTotalBytesWaiting(serialPort_t *instance)
uint8_t serialRxBytesWaiting(serialPort_t *instance)
{
return instance->vTable->serialTotalBytesWaiting(instance);
return instance->vTable->serialTotalRxWaiting(instance);
}
uint8_t serialTxBytesFree(serialPort_t *instance)
{
return instance->vTable->serialTotalTxFree(instance);
}
uint8_t serialRead(serialPort_t *instance)

View File

@ -36,7 +36,7 @@ typedef enum portOptions_t {
typedef void (*serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app
typedef struct serialPort {
typedef struct serialPort_s {
const struct serialPortVTable *vTable;
@ -62,7 +62,8 @@ typedef struct serialPort {
struct serialPortVTable {
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
uint8_t (*serialTotalBytesWaiting)(serialPort_t *instance);
uint8_t (*serialTotalRxWaiting)(serialPort_t *instance);
uint8_t (*serialTotalTxFree)(serialPort_t *instance);
uint8_t (*serialRead)(serialPort_t *instance);
@ -79,7 +80,8 @@ struct serialPortVTable {
};
void serialWrite(serialPort_t *instance, uint8_t ch);
uint8_t serialTotalBytesWaiting(serialPort_t *instance);
uint8_t serialRxBytesWaiting(serialPort_t *instance);
uint8_t serialTxBytesFree(serialPort_t *instance);
uint8_t serialRead(serialPort_t *instance);
void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate);
void serialSetMode(serialPort_t *instance, portMode_t mode);

View File

@ -403,7 +403,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
}
}
uint8_t softSerialTotalBytesWaiting(serialPort_t *instance)
uint8_t softSerialRxBytesWaiting(serialPort_t *instance)
{
if ((instance->mode & MODE_RX) == 0) {
return 0;
@ -414,6 +414,19 @@ uint8_t softSerialTotalBytesWaiting(serialPort_t *instance)
return (s->port.rxBufferHead - s->port.rxBufferTail) & (s->port.rxBufferSize - 1);
}
uint8_t softSerialTxBytesFree(serialPort_t *instance)
{
if ((instance->mode & MODE_TX) == 0) {
return 0;
}
softSerial_t *s = (softSerial_t *)instance;
uint8_t bytesUsed = (s->port.txBufferHead - s->port.txBufferTail) & (s->port.txBufferSize - 1);
return (s->port.txBufferSize - 1) - bytesUsed;
}
uint8_t softSerialReadByte(serialPort_t *instance)
{
uint8_t ch;
@ -422,7 +435,7 @@ uint8_t softSerialReadByte(serialPort_t *instance)
return 0;
}
if (softSerialTotalBytesWaiting(instance) == 0) {
if (softSerialRxBytesWaiting(instance) == 0) {
return 0;
}
@ -460,7 +473,8 @@ bool isSoftSerialTransmitBufferEmpty(serialPort_t *instance)
const struct serialPortVTable softSerialVTable[] = {
{
softSerialWriteByte,
softSerialTotalBytesWaiting,
softSerialRxBytesWaiting,
softSerialTxBytesFree,
softSerialReadByte,
softSerialSetBaudRate,
isSoftSerialTransmitBufferEmpty,

View File

@ -28,7 +28,8 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
// serialPort API
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);
uint8_t softSerialTotalBytesWaiting(serialPort_t *instance);
uint8_t softSerialRxBytesWaiting(serialPort_t *instance);
uint8_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

@ -211,7 +211,7 @@ void uartStartTxDMA(uartPort_t *s)
DMA_Cmd(s->txDMAChannel, ENABLE);
}
uint8_t uartTotalBytesWaiting(serialPort_t *instance)
uint8_t uartTotalRxBytesWaiting(serialPort_t *instance)
{
uartPort_t *s = (uartPort_t*)instance;
if (s->rxDMAChannel) {
@ -230,6 +230,41 @@ uint8_t uartTotalBytesWaiting(serialPort_t *instance)
}
}
uint8_t uartTotalTxBytesFree(serialPort_t *instance)
{
uartPort_t *s = (uartPort_t*)instance;
uint32_t bytesUsed;
if (s->port.txBufferHead >= s->port.txBufferTail) {
bytesUsed = s->port.txBufferHead - s->port.txBufferTail;
} else {
bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail;
}
if (s->txDMAChannel) {
/*
* When we queue up a DMA request, we advance the Tx buffer tail before the transfer finishes, so we must add
* the remaining size of that in-progress transfer here instead:
*/
bytesUsed += s->txDMAChannel->CNDTR;
/*
* If the Tx buffer is being written to very quickly, we might have advanced the head into the buffer
* space occupied by the current DMA transfer. In that case the "bytesUsed" total will actually end up larger
* than the total Tx buffer size, because we'll end up transmitting the same buffer region twice. (So we'll be
* transmitting a garbage mixture of old and new bytes).
*
* Be kind to callers and pretend like our buffer can only ever be 100% full.
*/
if (bytesUsed >= s->port.txBufferSize - 1) {
return 0;
}
}
return (s->port.txBufferSize - 1) - bytesUsed;
}
bool isUartTransmitBufferEmpty(serialPort_t *instance)
{
uartPort_t *s = (uartPort_t *)instance;
@ -281,7 +316,8 @@ void uartWrite(serialPort_t *instance, uint8_t ch)
const struct serialPortVTable uartVTable[] = {
{
uartWrite,
uartTotalBytesWaiting,
uartTotalRxBytesWaiting,
uartTotalTxBytesFree,
uartRead,
uartSetBaudRate,
isUartTransmitBufferEmpty,

View File

@ -19,6 +19,10 @@
// Since serial ports can be used for any function these buffer sizes should be equal
// The two largest things that need to be sent are: 1, MSP responses, 2, UBLOX SVINFO packet.
// Size must be a power of two due to various optimizations which use 'and' instead of 'mod'
// Various serial routines return the buffer occupied size as uint8_t which would need to be extended in order to
// increase size further.
#define UART1_RX_BUFFER_SIZE 256
#define UART1_TX_BUFFER_SIZE 256
#define UART2_RX_BUFFER_SIZE 256
@ -48,7 +52,8 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
// serialPort API
void uartWrite(serialPort_t *instance, uint8_t ch);
uint8_t uartTotalBytesWaiting(serialPort_t *instance);
uint8_t uartTotalRxBytesWaiting(serialPort_t *instance);
uint8_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

@ -128,18 +128,12 @@ static void usbVcpEndWrite(serialPort_t *instance)
usbVcpFlush(port);
}
static const struct serialPortVTable usbVTable[] = {
{
.serialWrite = usbVcpWrite,
.serialTotalBytesWaiting = usbVcpAvailable,
.serialRead = usbVcpRead,
.serialSetBaudRate = usbVcpSetBaudRate,
.isSerialTransmitBufferEmpty = isUsbVcpTransmitBufferEmpty,
.setMode = usbVcpSetMode,
.beginWrite = usbVcpBeginWrite,
.endWrite = usbVcpEndWrite,
}
};
uint8_t usbTxBytesFree() {
// Because we block upon transmit and don't buffer bytes, our "buffer" capacity is effectively unlimited.
return 255;
}
const struct serialPortVTable usbVTable[] = { { usbVcpWrite, usbVcpAvailable, usbTxBytesFree, usbVcpRead, usbVcpSetBaudRate, isUsbVcpTransmitBufferEmpty, usbVcpSetMode } };
serialPort_t *usbVcpOpen(void)
{

View File

@ -270,7 +270,7 @@ void calculateEstimatedAltitude(uint32_t currentTime)
BaroAlt = sonarAlt;
} else {
BaroAlt -= baroAlt_offset;
if (sonarAlt > 0) {
if (sonarAlt > 0 && sonarAlt <= 300) {
sonarTransition = (300 - sonarAlt) / 100.0f;
BaroAlt = sonarAlt * sonarTransition + BaroAlt * (1.0f - sonarTransition);
}

View File

@ -92,6 +92,13 @@ void imuConfigure(
throttleAngleScale = calculateThrottleAngleScale(throttle_correction_angle);
}
void imuInit(void)
{
smallAngle = lrintf(acc_1G * cos_approx(degreesToRadians(imuRuntimeConfig->small_angle)));
accVelScale = 9.80665f / acc_1G / 10000.0f;
gyroScaleRad = gyro.scale * (M_PIf / 180.0f) * 0.000001f;
}
float calculateThrottleAngleScale(uint16_t throttle_correction_angle)
{
return (1800.0f / M_PIf) * (900.0f / throttle_correction_angle);

View File

@ -21,7 +21,7 @@
#define LOWPASS_NUM_COEF 3
#define LPF_ROUND(x) (x < 0 ? (x - 0.5f) : (x + 0.5f))
typedef struct lowpass_t {
typedef struct lowpass_s {
bool init;
int16_t freq; // Normalized freq in 1/1000ths
float bf[LOWPASS_NUM_COEF];

View File

@ -783,10 +783,20 @@ void mixTable(void)
motor[i] -= maxThrottleDifference;
if (feature(FEATURE_3D)) {
if ((rcData[THROTTLE]) > rxConfig->midrc) {
motor[i] = constrain(motor[i], flight3DConfig->deadband3d_high, escAndServoConfig->maxthrottle);
if (mixerConfig->pid_at_min_throttle
|| rcData[THROTTLE] <= rxConfig->midrc - flight3DConfig->deadband3d_throttle
|| rcData[THROTTLE] >= rxConfig->midrc + flight3DConfig->deadband3d_throttle) {
if (rcData[THROTTLE] > rxConfig->midrc) {
motor[i] = constrain(motor[i], flight3DConfig->deadband3d_high, escAndServoConfig->maxthrottle);
} else {
motor[i] = constrain(motor[i], escAndServoConfig->mincommand, flight3DConfig->deadband3d_low);
}
} else {
motor[i] = constrain(motor[i], escAndServoConfig->mincommand, flight3DConfig->deadband3d_low);
if (rcData[THROTTLE] > rxConfig->midrc) {
motor[i] = flight3DConfig->deadband3d_high;
} else {
motor[i] = flight3DConfig->deadband3d_low;
}
}
} else {
if (isFailsafeActive) {

View File

@ -54,7 +54,7 @@ typedef enum mixerMode
} mixerMode_e;
// Custom mixer data per motor
typedef struct motorMixer_t {
typedef struct motorMixer_s {
float throttle;
float roll;
float pitch;
@ -62,7 +62,7 @@ typedef struct motorMixer_t {
} motorMixer_t;
// Custom mixer configuration
typedef struct mixer_t {
typedef struct mixer_s {
uint8_t motorCount;
uint8_t useServo;
const motorMixer_t *motor;
@ -86,7 +86,7 @@ typedef struct flight3DConfig_s {
uint16_t deadband3d_throttle; // default throttle deadband from MIDRC
} flight3DConfig_t;
typedef struct airplaneConfig_t {
typedef struct airplaneConfig_s {
int8_t fixedwing_althold_dir; // +1 or -1 for pitch/althold gain. later check if need more than just sign
} airplaneConfig_t;
@ -150,7 +150,7 @@ typedef enum {
#define SERVO_FLAPPERONS_MIN SERVO_FLAPPERON_1
#define SERVO_FLAPPERONS_MAX SERVO_FLAPPERON_2
typedef struct servoMixer_t {
typedef struct servoMixer_s {
uint8_t targetChannel; // servo that receives the output of the rule
uint8_t inputSource; // input channel for this rule
int8_t rate; // range [-125;+125] ; can be used to adjust a rate 0-125% and a direction
@ -165,12 +165,12 @@ typedef struct servoMixer_t {
#define MAX_SERVO_BOXES 3
// Custom mixer configuration
typedef struct mixerRules_t {
typedef struct mixerRules_s {
uint8_t servoRuleCount;
const servoMixer_t *rule;
} mixerRules_t;
typedef struct servoParam_t {
typedef struct servoParam_s {
int16_t min; // servo min
int16_t max; // servo max
int16_t middle; // servo middle

View File

@ -23,14 +23,12 @@ typedef enum {
PAGE_BATTERY,
PAGE_SENSORS,
PAGE_RX,
PAGE_PROFILE
PAGE_PROFILE,
#ifdef GPS
,
PAGE_GPS
PAGE_GPS,
#endif
#ifdef ENABLE_DEBUG_OLED_PAGE
,
PAGE_DEBUG
PAGE_DEBUG,
#endif
} pageId_e;

View File

@ -114,11 +114,6 @@ uint32_t flashfsGetSize()
return m25p16_getGeometry()->totalSize;
}
const flashGeometry_t* flashfsGetGeometry()
{
return m25p16_getGeometry();
}
static uint32_t flashfsTransmitBufferUsed()
{
if (bufferHead >= bufferTail)
@ -127,6 +122,27 @@ static uint32_t flashfsTransmitBufferUsed()
return FLASHFS_WRITE_BUFFER_SIZE - bufferTail + bufferHead;
}
/**
* Get the size of the largest single write that flashfs could ever accept without blocking or data loss.
*/
uint32_t flashfsGetWriteBufferSize()
{
return FLASHFS_WRITE_BUFFER_USABLE;
}
/**
* Get the number of bytes that can currently be written to flashfs without any blocking or data loss.
*/
uint32_t flashfsGetWriteBufferFreeSpace()
{
return flashfsGetWriteBufferSize() - flashfsTransmitBufferUsed();
}
const flashGeometry_t* flashfsGetGeometry()
{
return m25p16_getGeometry();
}
/**
* Write the given buffers to flash sequentially at the current tail address, advancing the tail address after
* each write.

View File

@ -32,6 +32,8 @@ void flashfsEraseRange(uint32_t start, uint32_t end);
uint32_t flashfsGetSize();
uint32_t flashfsGetOffset();
uint32_t flashfsGetWriteBufferFreeSpace();
uint32_t flashfsGetWriteBufferSize();
int flashfsIdentifyStartOfFreeSpace();
const flashGeometry_t* flashfsGetGeometry();

View File

@ -99,7 +99,7 @@ static gpsConfig_t *gpsConfig;
static serialConfig_t *serialConfig;
static serialPort_t *gpsPort;
typedef struct gpsInitData_t {
typedef struct gpsInitData_s {
uint8_t index;
uint8_t baudrateIndex; // see baudRate_e
const char *ubx;
@ -360,7 +360,7 @@ void gpsThread(void)
{
// read out available GPS bytes
if (gpsPort) {
while (serialTotalBytesWaiting(gpsPort))
while (serialRxBytesWaiting(gpsPort))
gpsNewData(serialRead(gpsPort));
}
@ -1036,14 +1036,14 @@ void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort)
#endif
char c;
while(1) {
if (serialTotalBytesWaiting(gpsPort)) {
if (serialRxBytesWaiting(gpsPort)) {
LED0_ON;
c = serialRead(gpsPort);
gpsNewData(c);
serialWrite(gpsPassthroughPort, c);
LED0_OFF;
}
if (serialTotalBytesWaiting(gpsPassthroughPort)) {
if (serialRxBytesWaiting(gpsPassthroughPort)) {
LED1_ON;
serialWrite(gpsPort, serialRead(gpsPassthroughPort));
LED1_OFF;

View File

@ -81,7 +81,7 @@ typedef enum {
#define GPS_MESSAGE_STATE_ENTRY_COUNT (GPS_MESSAGE_STATE_MAX + 1)
typedef struct gpsData_t {
typedef struct gpsData_s {
uint8_t state; // GPS thread state. Used for detecting cable disconnects and configuring attached devices
uint8_t baudrateIndex; // index into auto-detecting or current baudrate
uint32_t errors; // gps error counter - crc error/lost of data/sync etc..

View File

@ -2183,7 +2183,7 @@ void cliProcess(void)
return;
}
while (serialTotalBytesWaiting(cliPort)) {
while (serialRxBytesWaiting(cliPort)) {
uint8_t c = serialRead(cliPort);
if (c == '\t' || c == '?') {
// do tab completion

View File

@ -1892,7 +1892,7 @@ void mspProcess(void)
setCurrentPort(candidatePort);
while (serialTotalBytesWaiting(mspSerialPort)) {
while (serialRxBytesWaiting(mspSerialPort)) {
uint8_t c = serialRead(mspSerialPort);
bool consumed = mspProcessReceivedData(c);

View File

@ -515,7 +515,7 @@ void init(void)
void processLoopback(void) {
if (loopbackPort) {
uint8_t bytesWaiting;
while ((bytesWaiting = serialTotalBytesWaiting(loopbackPort))) {
while ((bytesWaiting = serialRxBytesWaiting(loopbackPort))) {
uint8_t b = serialRead(loopbackPort);
serialWrite(loopbackPort, b);
};

View File

@ -27,6 +27,7 @@
#include "common/axis.h"
#include "common/color.h"
#include "common/filter.h"
#include "common/utils.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
@ -242,14 +243,14 @@ void annexCode(void)
}
if (feature(FEATURE_VBAT)) {
if ((int32_t)(currentTime - vbatLastServiced) >= VBATINTERVAL) {
if (cmp32(currentTime, vbatLastServiced) >= VBATINTERVAL) {
vbatLastServiced = currentTime;
updateBattery();
}
}
if (feature(FEATURE_CURRENT_METER)) {
int32_t ibatTimeSinceLastServiced = (int32_t) (currentTime - ibatLastServiced);
int32_t ibatTimeSinceLastServiced = cmp32(currentTime, ibatLastServiced);
if (ibatTimeSinceLastServiced >= IBATINTERVAL) {
ibatLastServiced = currentTime;
@ -465,16 +466,14 @@ void executePeriodicTasks(void)
#if defined(BARO) || defined(SONAR)
case CALCULATE_ALTITUDE_TASK:
#if defined(BARO) && !defined(SONAR)
if (sensors(SENSOR_BARO) && isBaroReady()) {
if (false
#if defined(BARO)
|| (sensors(SENSOR_BARO) && isBaroReady())
#endif
#if defined(BARO) && defined(SONAR)
if ((sensors(SENSOR_BARO) && isBaroReady()) || sensors(SENSOR_SONAR)) {
#endif
#if !defined(BARO) && defined(SONAR)
if (sensors(SENSOR_SONAR)) {
#if defined(SONAR)
|| sensors(SENSOR_SONAR)
#endif
) {
calculateEstimatedAltitude(currentTime);
}
break;

View File

@ -82,7 +82,7 @@ bool sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa
{
int b;
for (b = 0; b < SBUS_MAX_CHANNEL; b++)
sbusChannelData[b] = (1.6f * rxConfig->midrc) - 1408;
sbusChannelData[b] = (16 * rxConfig->midrc) / 10 - 1408;
if (callback)
*callback = sbusReadRawRC;
rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL;

View File

@ -1,21 +0,0 @@
/*
*****************************************************************************
**
** File : stm32_flash.ld
**
** Abstract : Linker script for STM32F103CB Device with
** 128KByte FLASH, 20KByte RAM
**
*****************************************************************************
*/
/* Specify the memory areas. */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08003000, LENGTH = 126K - 0x03000 /* last 2kb used for config storage first 12k for OP Bootloader*/
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
INCLUDE "stm32_flash.ld"

View File

@ -374,7 +374,7 @@ static void processBinaryModeRequest(uint8_t address) {
static void flushHottRxBuffer(void)
{
while (serialTotalBytesWaiting(hottPort) > 0) {
while (serialRxBytesWaiting(hottPort) > 0) {
serialRead(hottPort);
}
}
@ -383,7 +383,7 @@ static void hottCheckSerialData(uint32_t currentMicros)
{
static bool lookingForRequest = true;
uint8_t bytesWaiting = serialTotalBytesWaiting(hottPort);
uint8_t bytesWaiting = serialRxBytesWaiting(hottPort);
if (bytesWaiting <= 1) {
return;

View File

@ -161,7 +161,7 @@ static void smartPortDataReceive(uint16_t c)
static uint8_t lastChar;
if (lastChar == FSSP_START_STOP) {
smartPortState = SPSTATE_WORKING;
if (c == FSSP_SENSOR_ID1 && (serialTotalBytesWaiting(smartPortSerialPort) == 0)) {
if (c == FSSP_SENSOR_ID1 && (serialRxBytesWaiting(smartPortSerialPort) == 0)) {
smartPortLastRequestTime = now;
smartPortHasRequest = 1;
// we only responde to these IDs
@ -283,7 +283,7 @@ void handleSmartPortTelemetry(void)
return;
}
while (serialTotalBytesWaiting(smartPortSerialPort) > 0) {
while (serialRxBytesWaiting(smartPortSerialPort) > 0) {
uint8_t c = serialRead(smartPortSerialPort);
smartPortDataReceive(c);
}

View File

@ -22,7 +22,7 @@ extern "C" {
extern uint32_t bmp280_up;
extern uint32_t bmp280_ut;
typedef struct bmp280_calib_param_t {
typedef struct bmp280_calib_param_s {
uint16_t dig_T1; /* calibration T1 data */
int16_t dig_T2; /* calibration T2 data */
int16_t dig_T3; /* calibration T3 data */

View File

@ -23,12 +23,12 @@ extern "C" {
#include "unittest_macros.h"
#include "gtest/gtest.h"
typedef struct zigzagEncodingExpectation_t {
typedef struct zigzagEncodingExpectation_s {
int32_t input;
uint32_t expected;
} zigzagEncodingExpectation_t;
typedef struct floatToIntEncodingExpectation_t {
typedef struct floatToIntEncodingExpectation_s {
float input;
uint32_t expected;
} floatToIntEncodingExpectation_t;

View File

@ -177,7 +177,12 @@ uint32_t millis(void) {
uint32_t micros(void) { return 0; }
uint8_t serialTotalBytesWaiting(serialPort_t *instance) {
uint8_t serialRxBytesWaiting(serialPort_t *instance) {
UNUSED(instance);
return 0;
}
uint8_t serialTxBytesFree(serialPort_t *instance) {
UNUSED(instance);
return 0;
}