1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-23 16:25:26 +03:00

Merge remote-tracking branch 'upstream/master' into abo_wp_mission_flight_select

This commit is contained in:
breadoven 2022-08-23 00:23:40 +01:00
commit cf1fe41990
72 changed files with 1584 additions and 91 deletions

View file

@ -57,6 +57,9 @@ To perform the restore simply paste the saved commands in the Configurator CLI t
After restoring it's always a good idea to `dump` or `diff` the settings once again and compare the output with previous one to verify if everything is set as it should be. After restoring it's always a good idea to `dump` or `diff` the settings once again and compare the output with previous one to verify if everything is set as it should be.
## Flight Controller opereration while connected to the CLI
While connected to the CLI, all Logical Switches are temporarily disabled (5.1.0 onwards).
## CLI Command Reference ## CLI Command Reference

View file

@ -18,6 +18,11 @@
* SBUS pin is connected to UART2 * SBUS pin is connected to UART2
* SmartPort telemetry can be setup with `SoftwareSerial` feature turned on, SmartPort configured in SoftwareSerial1 and receiver connected to UART2 TX pad * SmartPort telemetry can be setup with `SoftwareSerial` feature turned on, SmartPort configured in SoftwareSerial1 and receiver connected to UART2 TX pad
### Alternate targets
#### MATEKF045SE_PINIO
`MATEKF045SE_PINIO` replaces UART 6 (TX) with a pad that can be used for PINIO
## Where to buy: ## Where to buy:
* [Banggood](https://inavflight.com/shop/p/MATEKF405WING) * [Banggood](https://inavflight.com/shop/p/MATEKF405WING)

View file

@ -0,0 +1,11 @@
# Software In The Loop (HITL) plugin for X-Plane 11
**Hardware-in-the-loop (HITL) simulation**, is a technique that is used in the development and testing of complex real-time embedded systems.
**X-Plane** is a flight simulation engine series developed and published by Laminar Research https://www.x-plane.com/
**INAV-X-Plane-HITL** is plugin for **X-Plane** for testing and developing flight controllers with **INAV flight controller firmware**
https://github.com/iNavFlight/inav.
HITL technique can be used to test features during development. Please check page above for installation instructions.

View file

@ -1627,7 +1627,7 @@ static void loadMainState(timeUs_t currentTimeUs)
#endif #endif
#ifdef USE_PITOT #ifdef USE_PITOT
blackboxCurrent->airSpeed = pitot.airSpeed; blackboxCurrent->airSpeed = getAirspeedEstimate();
#endif #endif
#ifdef USE_RANGEFINDER #ifdef USE_RANGEFINDER

View file

@ -250,10 +250,12 @@ static const OSD_Entry cmsx_menuPidGpsnavEntries[] =
OTHER_PIDFF_ENTRY("POS P", &cmsx_pidPosXY.P), OTHER_PIDFF_ENTRY("POS P", &cmsx_pidPosXY.P),
OTHER_PIDFF_ENTRY("POS I", &cmsx_pidPosXY.I), OTHER_PIDFF_ENTRY("POS I", &cmsx_pidPosXY.I),
OTHER_PIDFF_ENTRY("POS D", &cmsx_pidPosXY.D),
OTHER_PIDFF_ENTRY("POSR P", &cmsx_pidVelXY.P), OTHER_PIDFF_ENTRY("VEL P", &cmsx_pidVelXY.P),
OTHER_PIDFF_ENTRY("POSR I", &cmsx_pidVelXY.I), OTHER_PIDFF_ENTRY("VEL I", &cmsx_pidVelXY.I),
OTHER_PIDFF_ENTRY("POSR D", &cmsx_pidVelXY.D), OTHER_PIDFF_ENTRY("VEL D", &cmsx_pidVelXY.D),
OTHER_PIDFF_ENTRY("VEL FF", &cmsx_pidVelXY.FF),
OSD_BACK_AND_END_ENTRY, OSD_BACK_AND_END_ENTRY,
}; };

View file

@ -107,7 +107,7 @@ static i2cState_t i2cState[I2CDEV_COUNT];
void i2cSetSpeed(uint8_t speed) void i2cSetSpeed(uint8_t speed)
{ {
for (unsigned int i = 0; i < sizeof(i2cHardwareMap) / sizeof(i2cHardwareMap[0]); i++) { for (unsigned int i = 0; i < ARRAYLEN(i2cHardwareMap); i++) {
i2cHardwareMap[i].speed = speed; i2cHardwareMap[i].speed = speed;
} }
} }

View file

@ -458,7 +458,7 @@ static void i2cStateMachine(i2cBusState_t * i2cBusState, const timeUs_t currentT
void i2cSetSpeed(uint8_t speed) void i2cSetSpeed(uint8_t speed)
{ {
for (unsigned int i = 0; i < sizeof(i2cHardwareMap) / sizeof(i2cHardwareMap[0]); i++) { for (unsigned int i = 0; i < ARRAYLEN(i2cHardwareMap); i++) {
i2cHardwareMap[i].speed = speed; i2cHardwareMap[i].speed = speed;
} }
} }

View file

@ -31,6 +31,7 @@
#include "drivers/time.h" #include "drivers/time.h"
#include "fc/settings.h" #include "fc/settings.h"
#include "fc/runtime_config.h"
#define SW_BLINK_CYCLE_MS 200 // 200ms on / 200ms off #define SW_BLINK_CYCLE_MS 200 // 200ms on / 200ms off
@ -176,6 +177,18 @@ int displayWriteChar(displayPort_t *instance, uint8_t x, uint8_t y, uint16_t c)
if (instance->maxChar == 0) { if (instance->maxChar == 0) {
displayUpdateMaxChar(instance); displayUpdateMaxChar(instance);
} }
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) {
//some FCs do not power max7456 from USB power
//driver can not read font metadata
//chip assumed to not support second bank of font
//artifical horizon, variometer and home direction are not drawn ( display.c: displayUpdateMaxChar())
//return dummy metadata to let all OSD elements to work in simulator mode
instance->maxChar = 512;
}
#endif
if (c > instance->maxChar) { if (c > instance->maxChar) {
return -1; return -1;
} }

View file

@ -123,7 +123,7 @@ uint32_t dmaGetChannelByTag(dmaTag_t tag)
DMA_t dmaGetByRef(const DMA_Stream_TypeDef* ref) DMA_t dmaGetByRef(const DMA_Stream_TypeDef* ref)
{ {
for (unsigned i = 0; i < (sizeof(dmaDescriptors) / sizeof(dmaDescriptors[0])); i++) { for (unsigned i = 0; i < ARRAYLEN(dmaDescriptors); i++) {
if (ref == dmaDescriptors[i].ref) { if (ref == dmaDescriptors[i].ref) {
return &dmaDescriptors[i]; return &dmaDescriptors[i];
} }

View file

@ -122,7 +122,7 @@ uint32_t dmaGetChannelByTag(dmaTag_t tag)
DMA_t dmaGetByRef(const DMA_Stream_TypeDef* ref) DMA_t dmaGetByRef(const DMA_Stream_TypeDef* ref)
{ {
for (unsigned i = 0; i < (sizeof(dmaDescriptors) / sizeof(dmaDescriptors[0])); i++) { for (unsigned i = 0; i < ARRAYLEN(dmaDescriptors); i++) {
if (ref == dmaDescriptors[i].ref) { if (ref == dmaDescriptors[i].ref) {
return &dmaDescriptors[i]; return &dmaDescriptors[i];
} }

View file

@ -118,7 +118,7 @@ void dmaSetHandler(DMA_t dma, dmaCallbackHandlerFuncPtr callback, uint32_t prior
DMA_t dmaGetByRef(const DMA_Stream_TypeDef* ref) DMA_t dmaGetByRef(const DMA_Stream_TypeDef* ref)
{ {
for (unsigned i = 0; i < (sizeof(dmaDescriptors) / sizeof(dmaDescriptors[0])); i++) { for (unsigned i = 0; i < ARRAYLEN(dmaDescriptors); i++) {
if (ref == dmaDescriptors[i].ref) { if (ref == dmaDescriptors[i].ref) {
return &dmaDescriptors[i]; return &dmaDescriptors[i];
} }

View file

@ -80,7 +80,7 @@ static bool flashDeviceInit(void)
{ {
bool detected = false; bool detected = false;
for (uint32_t idx = 0; idx <= sizeof(flashDrivers) / sizeof(flashDrivers[0]); idx++) for (uint32_t idx = 0; idx <= ARRAYLEN(flashDrivers); idx++)
{ {
detected = flashDrivers[idx].init(0); detected = flashDrivers[idx].init(0);
if (detected) if (detected)

View file

@ -301,7 +301,7 @@ static void w25n01g_programDataLoad(uint16_t columnAddress, const uint8_t *data,
uint8_t cmd[3] = {W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff}; uint8_t cmd[3] = {W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff};
busTransferDescriptor_t transferDescr[] = {{.length = sizeof(cmd), .rxBuf = NULL, .txBuf = cmd}, {.length = length, .rxBuf = NULL, .txBuf = (uint8_t *)data}}; busTransferDescriptor_t transferDescr[] = {{.length = sizeof(cmd), .rxBuf = NULL, .txBuf = cmd}, {.length = length, .rxBuf = NULL, .txBuf = (uint8_t *)data}};
busTransferMultiple(busDev, transferDescr, sizeof(transferDescr) / sizeof(transferDescr[0])); busTransferMultiple(busDev, transferDescr, ARRAYLEN(transferDescr));
w25n01g_setTimeout(W25N01G_TIMEOUT_PAGE_PROGRAM_MS); w25n01g_setTimeout(W25N01G_TIMEOUT_PAGE_PROGRAM_MS);
} }
@ -313,7 +313,7 @@ static void w25n01g_randomProgramDataLoad(uint16_t columnAddress, const uint8_t
uint8_t cmd[3] = {W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff}; uint8_t cmd[3] = {W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff};
busTransferDescriptor_t transferDescr[] = {{.length = sizeof(cmd), .rxBuf = NULL, .txBuf = cmd}, {.length = length, .rxBuf = NULL, .txBuf = (uint8_t *)data}}; busTransferDescriptor_t transferDescr[] = {{.length = sizeof(cmd), .rxBuf = NULL, .txBuf = cmd}, {.length = length, .rxBuf = NULL, .txBuf = (uint8_t *)data}};
busTransferMultiple(busDev, transferDescr, sizeof(transferDescr) / sizeof(transferDescr[0])); busTransferMultiple(busDev, transferDescr, ARRAYLEN(transferDescr));
w25n01g_setTimeout(W25N01G_TIMEOUT_PAGE_PROGRAM_MS); w25n01g_setTimeout(W25N01G_TIMEOUT_PAGE_PROGRAM_MS);
} }
@ -489,7 +489,7 @@ int w25n01g_readBytes(uint32_t address, uint8_t *buffer, int length)
const uint8_t cmd[4] = {W25N01G_INSTRUCTION_READ_DATA, (column >> 8) & 0xff, (column >> 0) & 0xff, 0}; const uint8_t cmd[4] = {W25N01G_INSTRUCTION_READ_DATA, (column >> 8) & 0xff, (column >> 0) & 0xff, 0};
busTransferDescriptor_t readDescr[] = {{.length = sizeof(cmd), .rxBuf = NULL, .txBuf = cmd}, {.length = transferLength, .rxBuf = buffer, .txBuf = NULL}}; busTransferDescriptor_t readDescr[] = {{.length = sizeof(cmd), .rxBuf = NULL, .txBuf = cmd}, {.length = transferLength, .rxBuf = buffer, .txBuf = NULL}};
busTransferMultiple(busDev, readDescr, sizeof(readDescr) / sizeof(readDescr[0])); busTransferMultiple(busDev, readDescr, ARRAYLEN(readDescr));
if (!w25n01g_waitForReady(W25N01G_TIMEOUT_PAGE_READ_MS)) { if (!w25n01g_waitForReady(W25N01G_TIMEOUT_PAGE_READ_MS)) {
return 0; return 0;
@ -530,7 +530,7 @@ int w25n01g_readExtensionBytes(uint32_t address, uint8_t *buffer, int length)
cmd[3] = 0; cmd[3] = 0;
busTransferDescriptor_t readDescr[] = {{.length = sizeof(cmd), .rxBuf = NULL, .txBuf = cmd}, {.length = length, .rxBuf = buffer, .txBuf = NULL}}; busTransferDescriptor_t readDescr[] = {{.length = sizeof(cmd), .rxBuf = NULL, .txBuf = cmd}, {.length = length, .rxBuf = buffer, .txBuf = NULL}};
busTransferMultiple(busDev, readDescr, sizeof(readDescr) / sizeof(readDescr[0])); busTransferMultiple(busDev, readDescr, ARRAYLEN(readDescr));
w25n01g_setTimeout(W25N01G_TIMEOUT_PAGE_READ_MS); w25n01g_setTimeout(W25N01G_TIMEOUT_PAGE_READ_MS);

View file

@ -60,7 +60,7 @@ const pinioHardware_t pinioHardware[] = {
#endif #endif
}; };
const int pinioHardwareCount = sizeof(pinioHardware) / sizeof(pinioHardware[0]); const int pinioHardwareCount = ARRAYLEN(pinioHardware);
/*** Runtime configuration ***/ /*** Runtime configuration ***/
typedef struct pinioRuntime_s { typedef struct pinioRuntime_s {

View file

@ -27,6 +27,7 @@
#include "drivers/pwm_mapping.h" #include "drivers/pwm_mapping.h"
#include "drivers/pwm_output.h" #include "drivers/pwm_output.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/runtime_config.h"
#include "sound_beeper.h" #include "sound_beeper.h"
@ -45,6 +46,14 @@ void systemBeep(bool onoff)
UNUSED(onoff); UNUSED(onoff);
#else #else
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) {
if (simulatorData.flags & SIMU_MUTE_BEEPER) {
onoff = false;
}
}
#endif
if (beeperConfig()->pwmMode) { if (beeperConfig()->pwmMode) {
pwmWriteBeeper(onoff); pwmWriteBeeper(onoff);
beeperState = onoff; beeperState = onoff;

View file

@ -3639,7 +3639,7 @@ static void printConfig(const char *cmdline, bool doDiff)
printMotorMix(dumpMask, primaryMotorMixer_CopyArray, primaryMotorMixer(0)); printMotorMix(dumpMask, primaryMotorMixer_CopyArray, primaryMotorMixer(0));
// print custom servo mixer if exists // print custom servo mixer if exists
cliPrintHashLine("servo mix"); cliPrintHashLine("servo mixer");
cliDumpPrintLinef(dumpMask, customServoMixers_CopyArray[0].rate == 0, "smix reset\r\n"); cliDumpPrintLinef(dumpMask, customServoMixers_CopyArray[0].rate == 0, "smix reset\r\n");
printServoMix(dumpMask, customServoMixers_CopyArray, customServoMixers(0)); printServoMix(dumpMask, customServoMixers_CopyArray, customServoMixers(0));
@ -3651,16 +3651,6 @@ static void printConfig(const char *cmdline, bool doDiff)
cliPrintHashLine("safehome"); cliPrintHashLine("safehome");
printSafeHomes(dumpMask, safeHomeConfig_CopyArray, safeHomeConfig(0)); printSafeHomes(dumpMask, safeHomeConfig_CopyArray, safeHomeConfig(0));
#endif #endif
#ifdef USE_PROGRAMMING_FRAMEWORK
cliPrintHashLine("logic");
printLogic(dumpMask, logicConditions_CopyArray, logicConditions(0));
cliPrintHashLine("gvar");
printGvar(dumpMask, globalVariableConfigs_CopyArray, globalVariableConfigs(0));
cliPrintHashLine("pid");
printPid(dumpMask, programmingPids_CopyArray, programmingPids(0));
#endif
cliPrintHashLine("feature"); cliPrintHashLine("feature");
printFeature(dumpMask, &featureConfig_Copy, featureConfig()); printFeature(dumpMask, &featureConfig_Copy, featureConfig());
@ -3716,6 +3706,17 @@ static void printConfig(const char *cmdline, bool doDiff)
printOsdLayout(dumpMask, &osdLayoutsConfig_Copy, osdLayoutsConfig(), -1, -1); printOsdLayout(dumpMask, &osdLayoutsConfig_Copy, osdLayoutsConfig(), -1, -1);
#endif #endif
#ifdef USE_PROGRAMMING_FRAMEWORK
cliPrintHashLine("logic");
printLogic(dumpMask, logicConditions_CopyArray, logicConditions(0));
cliPrintHashLine("global vars");
printGvar(dumpMask, globalVariableConfigs_CopyArray, globalVariableConfigs(0));
cliPrintHashLine("programmable pid controllers");
printPid(dumpMask, programmingPids_CopyArray, programmingPids(0));
#endif
cliPrintHashLine("master"); cliPrintHashLine("master");
dumpAllValues(MASTER_VALUE, dumpMask); dumpAllValues(MASTER_VALUE, dumpMask);
@ -3736,7 +3737,6 @@ static void printConfig(const char *cmdline, bool doDiff)
cliPrintLinef("profile %d", currentProfileIndexSave + 1); cliPrintLinef("profile %d", currentProfileIndexSave + 1);
cliPrintLinef("battery_profile %d", currentBatteryProfileIndexSave + 1); cliPrintLinef("battery_profile %d", currentBatteryProfileIndexSave + 1);
cliPrintHashLine("save configuration\r\nsave");
#ifdef USE_CLI_BATCH #ifdef USE_CLI_BATCH
batchModeEnabled = false; batchModeEnabled = false;
#endif #endif
@ -3755,6 +3755,10 @@ static void printConfig(const char *cmdline, bool doDiff)
cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask); cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask);
} }
if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
cliPrintHashLine("save configuration\r\nsave");
}
#ifdef USE_CLI_BATCH #ifdef USE_CLI_BATCH
if (batchModeEnabled) { if (batchModeEnabled) {
cliPrintHashLine("end the command batch"); cliPrintHashLine("end the command batch");

View file

@ -939,6 +939,9 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
} }
//Servos should be filtered or written only when mixer is using servos or special feaures are enabled //Servos should be filtered or written only when mixer is using servos or special feaures are enabled
#ifdef USE_SMULATOR
if (!ARMING_FLAG(SIMULATOR_MODE)) {
if (isServoOutputEnabled()) { if (isServoOutputEnabled()) {
writeServos(); writeServos();
} }
@ -946,6 +949,16 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
if (motorControlEnable) { if (motorControlEnable) {
writeMotors(); writeMotors();
} }
}
#else
if (isServoOutputEnabled()) {
writeServos();
}
if (motorControlEnable) {
writeMotors();
}
#endif
// Check if landed, FW and MR // Check if landed, FW and MR
if (STATE(ALTITUDE_CONTROL)) { if (STATE(ALTITUDE_CONTROL)) {

View file

@ -21,6 +21,7 @@
#include <string.h> #include <string.h>
#include <math.h> #include <math.h>
#include "common/log.h" //for MSP_SIMULATOR
#include "platform.h" #include "platform.h"
#include "blackbox/blackbox.h" #include "blackbox/blackbox.h"
@ -92,12 +93,15 @@
#include "io/serial_4way.h" #include "io/serial_4way.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "io/vtx_string.h" #include "io/vtx_string.h"
#include "io/gps_private.h" //for MSP_SIMULATOR
#include "msp/msp.h" #include "msp/msp.h"
#include "msp/msp_protocol.h" #include "msp/msp_protocol.h"
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
#include "navigation/navigation.h" #include "navigation/navigation.h"
#include "navigation/navigation_private.h" //for MSP_SIMULATOR
#include "navigation/navigation_pos_estimator_private.h" //for MSP_SIMULATOR
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/msp.h" #include "rx/msp.h"
@ -1424,7 +1428,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
case MSP2_INAV_AIR_SPEED: case MSP2_INAV_AIR_SPEED:
#ifdef USE_PITOT #ifdef USE_PITOT
sbufWriteU32(dst, pitot.airSpeed); sbufWriteU32(dst, getAirspeedEstimate());
#else #else
sbufWriteU32(dst, 0); sbufWriteU32(dst, 0);
#endif #endif
@ -2474,7 +2478,8 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
#ifdef USE_GPS #ifdef USE_GPS
case MSP_SET_RAW_GPS: case MSP_SET_RAW_GPS:
if (dataSize == 14) { if (dataSize == 14) {
if (sbufReadU8(src)) { gpsSol.fixType = sbufReadU8(src);
if (gpsSol.fixType) {
ENABLE_STATE(GPS_FIX); ENABLE_STATE(GPS_FIX);
} else { } else {
DISABLE_STATE(GPS_FIX); DISABLE_STATE(GPS_FIX);
@ -2485,7 +2490,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
gpsSol.numSat = sbufReadU8(src); gpsSol.numSat = sbufReadU8(src);
gpsSol.llh.lat = sbufReadU32(src); gpsSol.llh.lat = sbufReadU32(src);
gpsSol.llh.lon = sbufReadU32(src); gpsSol.llh.lon = sbufReadU32(src);
gpsSol.llh.alt = sbufReadU16(src); gpsSol.llh.alt = 100 * sbufReadU16(src); // require cm
gpsSol.groundSpeed = sbufReadU16(src); gpsSol.groundSpeed = sbufReadU16(src);
gpsSol.velNED[X] = 0; gpsSol.velNED[X] = 0;
gpsSol.velNED[Y] = 0; gpsSol.velNED[Y] = 0;
@ -3181,8 +3186,147 @@ static bool mspParameterGroupsCommand(sbuf_t *dst, sbuf_t *src)
return true; return true;
} }
#ifdef USE_SIMULATOR
bool isOSDTypeSupportedBySimulator(void)
{
displayPort_t *osdDisplayPort = osdGetDisplayPort();
return (osdDisplayPort && osdDisplayPort->cols == 30 && (osdDisplayPort->rows == 13 || osdDisplayPort->rows == 16));
}
void mspWriteSimulatorOSD(sbuf_t *dst)
{
//RLE encoding
//scan displayBuffer iteratively
//no more than 80+3+2 bytes output in single run
//0 and 255 are special symbols
//255 - font bank switch
//0 - font bank switch, blink switch and character repeat
static uint8_t osdPos_y = 0;
static uint8_t osdPos_x = 0;
if (isOSDTypeSupportedBySimulator())
{
displayPort_t *osdDisplayPort = osdGetDisplayPort();
sbufWriteU8(dst, osdPos_y | (osdDisplayPort->rows == 16 ? 128: 0));
sbufWriteU8(dst, osdPos_x);
int bytesCount = 0;
uint16_t c = 0;
textAttributes_t attr = 0;
bool highBank = false;
bool blink = false;
int count = 0;
int processedRows = 16;
while (bytesCount < 80) //whole response should be less 155 bytes at worst.
{
bool blink1;
uint16_t lastChar;
count = 0;
while ( true )
{
displayReadCharWithAttr(osdDisplayPort, osdPos_x, osdPos_y, &c, &attr);
if (c == 0 || c == 255) c = 32;
//REVIEW: displayReadCharWithAttr() should return mode with _TEXT_ATTRIBUTES_BLINK_BIT !
//for max7456 it returns mode with MAX7456_MODE_BLINK instead (wrong)
//because max7456ReadChar() does not decode from MAX7456_MODE_BLINK to _TEXT_ATTRIBUTES_BLINK_BIT
//it should!
//bool blink2 = TEXT_ATTRIBUTES_HAVE_BLINK(attr);
bool blink2 = attr & (1<<4); //MAX7456_MODE_BLINK
if (count == 0)
{
lastChar = c;
blink1 = blink2;
}
else if (lastChar != c || blink2 != blink1 || count == 63)
{
break;
}
count++;
osdPos_x++;
if (osdPos_x == 30)
{
osdPos_x = 0;
osdPos_y++;
processedRows--;
if (osdPos_y == 16)
{
osdPos_y = 0;
}
}
}
uint8_t cmd = 0;
if (blink1 != blink)
{
cmd |= 128;//switch blink attr
blink = blink1;
}
bool highBank1 = lastChar > 255;
if (highBank1 != highBank)
{
cmd |= 64;//switch bank attr
highBank = highBank1;
}
if (count == 1 && cmd == 64)
{
sbufWriteU8(dst, 255); //short command for bank switch
sbufWriteU8(dst, lastChar & 0xff);
bytesCount += 2;
}
else if (count > 2 || cmd !=0 )
{
cmd |= count; //long command for blink/bank switch and symbol repeat
sbufWriteU8(dst, 0);
sbufWriteU8(dst, cmd);
sbufWriteU8(dst, lastChar & 0xff);
bytesCount += 3;
}
else if (count == 2) //cmd == 0 here
{
sbufWriteU8(dst, lastChar & 0xff);
sbufWriteU8(dst, lastChar & 0xff);
bytesCount+=2;
}
else
{
sbufWriteU8(dst, lastChar & 0xff);
bytesCount++;
}
if ( processedRows <= 0 )
{
break;
}
}
sbufWriteU8(dst, 0); //command 0 with length=0 -> stop
sbufWriteU8(dst, 0);
}
else
{
sbufWriteU8(dst, 255);
}
}
#endif
bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResult_e *ret) bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResult_e *ret)
{ {
uint8_t tmp_u8;
const unsigned int dataSize = sbufBytesRemaining(src);
switch (cmdMSP) { switch (cmdMSP) {
case MSP_WP: case MSP_WP:
@ -3253,6 +3397,175 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
*ret = mspFcSafeHomeOutCommand(dst, src); *ret = mspFcSafeHomeOutCommand(dst, src);
break; break;
#ifdef USE_SIMULATOR
case MSP_SIMULATOR:
tmp_u8 = sbufReadU8(src); //MSP_SIMULATOR version
if (tmp_u8 != 2) break;
simulatorData.flags = sbufReadU8(src);
if ((simulatorData.flags & SIMU_ENABLE) == 0) {
if (ARMING_FLAG(SIMULATOR_MODE)) { // just once
DISABLE_ARMING_FLAG(SIMULATOR_MODE);
#ifdef USE_BARO
baroStartCalibration();
#endif
#ifdef USE_MAG
DISABLE_STATE(COMPASS_CALIBRATED);
compassInit();
#endif
simulatorData.flags = 0;
//review: many states were affected. reboot?
disarm(DISARM_SWITCH); //disarm to prevent motor output!!!
}
}
else if (!areSensorsCalibrating()) {
if (!ARMING_FLAG(SIMULATOR_MODE)) { // just once
#ifdef USE_BARO
baroStartCalibration();
#endif
#ifdef USE_MAG
if (compassConfig()->mag_hardware != MAG_NONE){
sensorsSet(SENSOR_MAG);
ENABLE_STATE(COMPASS_CALIBRATED);
DISABLE_ARMING_FLAG(ARMING_DISABLED_HARDWARE_FAILURE);
mag.magADC[X] = 800;
mag.magADC[Y] = 0;
mag.magADC[Z] = 0;
}
#endif
ENABLE_ARMING_FLAG(SIMULATOR_MODE);
LOG_D(SYSTEM, "Simulator enabled");
}
if (dataSize >= 14) {
if (feature(FEATURE_GPS) && ((simulatorData.flags & SIMU_HAS_NEW_GPS_DATA)!=0) ) {
gpsSol.fixType = sbufReadU8(src);
gpsSol.hdop = gpsSol.fixType == GPS_NO_FIX ? 9999 : 100;
gpsSol.flags.hasNewData = true;
gpsSol.numSat = sbufReadU8(src);
if (gpsSol.fixType != GPS_NO_FIX) {
gpsSol.flags.validVelNE = 1;
gpsSol.flags.validVelD = 1;
gpsSol.flags.validEPE = 1;
gpsSol.llh.lat = sbufReadU32(src);
gpsSol.llh.lon = sbufReadU32(src);
gpsSol.llh.alt = sbufReadU32(src);
gpsSol.groundSpeed = (int16_t)sbufReadU16(src);
gpsSol.groundCourse = (int16_t)sbufReadU16(src);
gpsSol.velNED[X] = (int16_t)sbufReadU16(src);
gpsSol.velNED[Y] = (int16_t)sbufReadU16(src);
gpsSol.velNED[Z] = (int16_t)sbufReadU16(src);
gpsSol.eph = 100;
gpsSol.epv = 100;
ENABLE_STATE(GPS_FIX);
// Feed data to navigation
gpsProcessNewSolutionData();
}
else {
sbufAdvance(src, 4 + 4 + 4 + 2 + 2 + 2 * 3);
// Feed data to navigation
gpsProcessNewSolutionData();
}
}
else {
sbufAdvance(src, 1 + 1 + 4 + 4 + 4 + 2 + 2 + 2 * 3);
}
if ((simulatorData.flags & SIMU_USE_SENSORS) == 0) {
attitude.values.roll = (int16_t)sbufReadU16(src);
attitude.values.pitch = (int16_t)sbufReadU16(src);
attitude.values.yaw = (int16_t)sbufReadU16(src);
}
else
{
sbufAdvance(src, 2*3);
}
acc.accADCf[X] = ((int16_t)sbufReadU16(src)) / 1000.0f;// acceleration in 1G units
acc.accADCf[Y] = ((int16_t)sbufReadU16(src)) / 1000.0f;
acc.accADCf[Z] = ((int16_t)sbufReadU16(src)) / 1000.0f;
acc.accVibeSq[X] = 0;
acc.accVibeSq[Y] = 0;
acc.accVibeSq[Z] = 0;
gyro.gyroADCf[X] = ((int16_t)sbufReadU16(src)) / 16.0f;
gyro.gyroADCf[Y] = ((int16_t)sbufReadU16(src)) / 16.0f;
gyro.gyroADCf[Z] = ((int16_t)sbufReadU16(src)) / 16.0f;
if (sensors(SENSOR_BARO))
{
baro.baroPressure = (int32_t)sbufReadU32(src);
baro.baroTemperature = 2500;
}
else {
sbufAdvance(src,4);
}
if (sensors(SENSOR_MAG))
{
mag.magADC[X] = ((int16_t)sbufReadU16(src)) / 20; //16000/20 = 800uT
mag.magADC[Y] = ((int16_t)sbufReadU16(src)) / 20;
mag.magADC[Z] = ((int16_t)sbufReadU16(src)) / 20;
}
else {
sbufAdvance(src, 2*3);
}
if (simulatorData.flags & SIMU_EXT_BATTERY_VOLTAGE) {
simulatorData.vbat = sbufReadU8(src);
}
else {
simulatorData.vbat = 126;
}
if (simulatorData.flags & SIMU_AIRSPEED) {
simulatorData.airSpeed = sbufReadU16(src);
}
}
else {
DISABLE_STATE(GPS_FIX);
}
}
sbufWriteU16(dst, (uint16_t)simulatorData.INPUT_STABILIZED_ROLL);
sbufWriteU16(dst, (uint16_t)simulatorData.INPUT_STABILIZED_PITCH);
sbufWriteU16(dst, (uint16_t)simulatorData.INPUT_STABILIZED_YAW);
sbufWriteU16(dst, (uint16_t)(ARMING_FLAG(ARMED) ? simulatorData.INPUT_STABILIZED_THROTTLE : -500));
simulatorData.debugIndex++;
if (simulatorData.debugIndex == 8) {
simulatorData.debugIndex = 0;
}
tmp_u8 = simulatorData.debugIndex |
((mixerConfig()->platformType == PLATFORM_AIRPLANE) ? 128 : 0) |
(ARMING_FLAG(ARMED) ? 64 : 0) |
(!feature(FEATURE_OSD) ? 32: 0) |
(!isOSDTypeSupportedBySimulator() ? 16: 0);
sbufWriteU8(dst, tmp_u8 );
sbufWriteU32(dst, debug[simulatorData.debugIndex]);
sbufWriteU16(dst, attitude.values.roll);
sbufWriteU16(dst, attitude.values.pitch);
sbufWriteU16(dst, attitude.values.yaw);
mspWriteSimulatorOSD(dst);
*ret = MSP_RESULT_ACK;
break;
#endif
default: default:
// Not handled // Not handled
return false; return false;

View file

@ -87,15 +87,15 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
{ .boxId = BOXUSER1, .boxName = "USER1", .permanentId = BOX_PERMANENT_ID_USER1 }, { .boxId = BOXUSER1, .boxName = "USER1", .permanentId = BOX_PERMANENT_ID_USER1 },
{ .boxId = BOXUSER2, .boxName = "USER2", .permanentId = BOX_PERMANENT_ID_USER2 }, { .boxId = BOXUSER2, .boxName = "USER2", .permanentId = BOX_PERMANENT_ID_USER2 },
{ .boxId = BOXUSER3, .boxName = "USER3", .permanentId = BOX_PERMANENT_ID_USER3 }, { .boxId = BOXUSER3, .boxName = "USER3", .permanentId = BOX_PERMANENT_ID_USER3 },
{ .boxId = BOXLOITERDIRCHN, .boxName = "LOITER CHANGE", .permanentId = 49 }, { .boxId = BOXLOITERDIRCHN, .boxName = "LOITER CHANGE", .permanentId = 50 },
{ .boxId = BOXMSPRCOVERRIDE, .boxName = "MSP RC OVERRIDE", .permanentId = 50 }, { .boxId = BOXMSPRCOVERRIDE, .boxName = "MSP RC OVERRIDE", .permanentId = 51 },
{ .boxId = BOXPREARM, .boxName = "PREARM", .permanentId = 51 }, { .boxId = BOXPREARM, .boxName = "PREARM", .permanentId = 52 },
{ .boxId = BOXTURTLE, .boxName = "TURTLE", .permanentId = 52 }, { .boxId = BOXTURTLE, .boxName = "TURTLE", .permanentId = 53 },
{ .boxId = BOXNAVCRUISE, .boxName = "NAV CRUISE", .permanentId = 53 }, { .boxId = BOXNAVCRUISE, .boxName = "NAV CRUISE", .permanentId = 54 },
{ .boxId = BOXAUTOLEVEL, .boxName = "AUTO LEVEL", .permanentId = 54 }, { .boxId = BOXAUTOLEVEL, .boxName = "AUTO LEVEL", .permanentId = 55 },
{ .boxId = BOXPLANWPMISSION, .boxName = "WP PLANNER", .permanentId = 55 }, { .boxId = BOXPLANWPMISSION, .boxName = "WP PLANNER", .permanentId = 56 },
{ .boxId = BOXSOARING, .boxName = "SOARING", .permanentId = 56 }, { .boxId = BOXSOARING, .boxName = "SOARING", .permanentId = 57 },
{ .boxId = BOXCHANGEMISSION, .boxName = "MISSION CHANGE", .permanentId = 57 }, { .boxId = BOXCHANGEMISSION, .boxName = "MISSION CHANGE", .permanentId = 58 },
{ .boxId = CHECKBOX_ITEM_COUNT, .boxName = NULL, .permanentId = 0xFF } { .boxId = CHECKBOX_ITEM_COUNT, .boxName = NULL, .permanentId = 0xFF }
}; };

View file

@ -306,7 +306,13 @@ void taskUpdateAux(timeUs_t currentTimeUs)
{ {
updatePIDCoefficients(); updatePIDCoefficients();
dynamicLpfGyroTask(); dynamicLpfGyroTask();
#ifdef USE_SIMULATOR
if (!ARMING_FLAG(SIMULATOR_MODE)) {
updateFixedWingLevelTrim(currentTimeUs); updateFixedWingLevelTrim(currentTimeUs);
}
#else
updateFixedWingLevelTrim(currentTimeUs);
#endif
} }
void fcTasksInit(void) void fcTasksInit(void)

View file

@ -95,8 +95,8 @@ typedef struct rcControlsConfig_s {
PG_DECLARE(rcControlsConfig_t, rcControlsConfig); PG_DECLARE(rcControlsConfig_t, rcControlsConfig);
typedef struct armingConfig_s { typedef struct armingConfig_s {
uint8_t fixed_wing_auto_arm; // Auto-arm fixed wing aircraft on throttle up and never disarm bool fixed_wing_auto_arm; // Auto-arm fixed wing aircraft on throttle up and never disarm
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value bool disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
uint16_t switchDisarmDelayMs; // additional delay between ARM box going off and actual disarm uint16_t switchDisarmDelayMs; // additional delay between ARM box going off and actual disarm
uint16_t prearmTimeoutMs; // duration for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout. uint16_t prearmTimeoutMs; // duration for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout.
} armingConfig_t; } armingConfig_t;

View file

@ -176,3 +176,10 @@ flightModeForTelemetry_e getFlightModeForTelemetry(void)
return STATE(AIRMODE_ACTIVE) ? FLM_ACRO_AIR : FLM_ACRO; return STATE(AIRMODE_ACTIVE) ? FLM_ACRO_AIR : FLM_ACRO;
} }
#ifdef USE_SIMULATOR
simulatorData_t simulatorData = {
flags: 0,
debugIndex: 0
};
#endif

View file

@ -21,6 +21,7 @@
typedef enum { typedef enum {
ARMED = (1 << 2), ARMED = (1 << 2),
WAS_EVER_ARMED = (1 << 3), WAS_EVER_ARMED = (1 << 3),
SIMULATOR_MODE = (1 << 4),
ARMING_DISABLED_FAILSAFE_SYSTEM = (1 << 7), ARMING_DISABLED_FAILSAFE_SYSTEM = (1 << 7),
ARMING_DISABLED_NOT_LEVEL = (1 << 8), ARMING_DISABLED_NOT_LEVEL = (1 << 8),
@ -164,6 +165,32 @@ typedef enum {
flightModeForTelemetry_e getFlightModeForTelemetry(void); flightModeForTelemetry_e getFlightModeForTelemetry(void);
#ifdef USE_SIMULATOR
typedef enum {
SIMU_ENABLE = (1 << 0),
SIMU_SIMULATE_BATTERY = (1 << 1),
SIMU_MUTE_BEEPER = (1 << 2),
SIMU_USE_SENSORS = (1 << 3),
SIMU_HAS_NEW_GPS_DATA = (1 << 4),
SIMU_EXT_BATTERY_VOLTAGE = (1 << 5),//extend MSP_SIMULATOR format 2
SIMU_AIRSPEED = (1 << 6)
} simulatorFlags_t;
typedef struct {
simulatorFlags_t flags;
uint8_t debugIndex;
uint8_t vbat; //126 ->12.6V
uint16_t airSpeed; //cm/s
int16_t INPUT_STABILIZED_ROLL;
int16_t INPUT_STABILIZED_PITCH;
int16_t INPUT_STABILIZED_YAW;
int16_t INPUT_STABILIZED_THROTTLE;
} simulatorData_t;
extern simulatorData_t simulatorData;
#endif
uint32_t enableFlightMode(flightModeFlags_e mask); uint32_t enableFlightMode(flightModeFlags_e mask);
uint32_t disableFlightMode(flightModeFlags_e mask); uint32_t disableFlightMode(flightModeFlags_e mask);

View file

@ -327,6 +327,12 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe
// Normalize to unit vector // Normalize to unit vector
vectorNormalize(&vMag, &vMag); vectorNormalize(&vMag, &vMag);
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) {
imuSetMagneticDeclination(0);
}
#endif
// Reference mag field vector heading is Magnetic North in EF. We compute that by rotating True North vector by declination and assuming Z-component is zero // Reference mag field vector heading is Magnetic North in EF. We compute that by rotating True North vector by declination and assuming Z-component is zero
// magnetometer error is cross product between estimated magnetic north and measured magnetic north (calculated in EF) // magnetometer error is cross product between estimated magnetic north and measured magnetic north (calculated in EF)
vectorCrossProduct(&vErr, &vMag, &vCorrectedMagNorth); vectorCrossProduct(&vErr, &vMag, &vCorrectedMagNorth);
@ -455,10 +461,19 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe
STATIC_UNIT_TESTED void imuUpdateEulerAngles(void) STATIC_UNIT_TESTED void imuUpdateEulerAngles(void)
{ {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE) && ((simulatorData.flags & SIMU_USE_SENSORS) == 0)) {
imuComputeQuaternionFromRPY(attitude.values.roll, attitude.values.pitch, attitude.values.yaw);
imuComputeRotationMatrix();
}
else
#endif
{
/* Compute pitch/roll angles */ /* Compute pitch/roll angles */
attitude.values.roll = RADIANS_TO_DECIDEGREES(atan2_approx(rMat[2][1], rMat[2][2])); attitude.values.roll = RADIANS_TO_DECIDEGREES(atan2_approx(rMat[2][1], rMat[2][2]));
attitude.values.pitch = RADIANS_TO_DECIDEGREES((0.5f * M_PIf) - acos_approx(-rMat[2][0])); attitude.values.pitch = RADIANS_TO_DECIDEGREES((0.5f * M_PIf) - acos_approx(-rMat[2][0]));
attitude.values.yaw = RADIANS_TO_DECIDEGREES(-atan2_approx(rMat[1][0], rMat[0][0])); attitude.values.yaw = RADIANS_TO_DECIDEGREES(-atan2_approx(rMat[1][0], rMat[0][0]));
}
if (attitude.values.yaw < 0) if (attitude.values.yaw < 0)
attitude.values.yaw += 3600; attitude.values.yaw += 3600;

View file

@ -379,7 +379,7 @@ bool pidInitFilters(void)
void pidResetTPAFilter(void) void pidResetTPAFilter(void)
{ {
if (usedPidControllerType == PID_TYPE_PIFF && currentControlRateProfile->throttle.fixedWingTauMs > 0) { if (usedPidControllerType == PID_TYPE_PIFF && currentControlRateProfile->throttle.fixedWingTauMs > 0) {
pt1FilterInitRC(&fixedWingTpaFilter, currentControlRateProfile->throttle.fixedWingTauMs * 1e-3f, TASK_PERIOD_HZ(TASK_AUX_RATE_HZ) * 1e-6f); pt1FilterInitRC(&fixedWingTpaFilter, MS2S(currentControlRateProfile->throttle.fixedWingTauMs), TASK_PERIOD_HZ(TASK_AUX_RATE_HZ) * 1e-6f);
pt1FilterReset(&fixedWingTpaFilter, getThrottleIdleValue()); pt1FilterReset(&fixedWingTpaFilter, getThrottleIdleValue());
} }
} }
@ -997,15 +997,13 @@ static void NOINLINE pidTurnAssistant(pidState_t *pidState, float bankAngleTarge
// yaw_rate = tan(roll_angle) * Gravity / forward_vel // yaw_rate = tan(roll_angle) * Gravity / forward_vel
#if defined(USE_PITOT) #if defined(USE_PITOT)
float airspeedForCoordinatedTurn = sensors(SENSOR_PITOT) ? float airspeedForCoordinatedTurn = sensors(SENSOR_PITOT) ? getAirspeedEstimate() : pidProfile()->fixedWingReferenceAirspeed;
pitot.airSpeed :
pidProfile()->fixedWingReferenceAirspeed;
#else #else
float airspeedForCoordinatedTurn = pidProfile()->fixedWingReferenceAirspeed; float airspeedForCoordinatedTurn = pidProfile()->fixedWingReferenceAirspeed;
#endif #endif
// Constrain to somewhat sane limits - 10km/h - 216km/h // Constrain to somewhat sane limits - 10km/h - 216km/h
airspeedForCoordinatedTurn = constrainf(airspeedForCoordinatedTurn, 300, 6000); airspeedForCoordinatedTurn = constrainf(airspeedForCoordinatedTurn, 300.0f, 6000.0f);
// Calculate rate of turn in Earth frame according to FAA's Pilot's Handbook of Aeronautical Knowledge // Calculate rate of turn in Earth frame according to FAA's Pilot's Handbook of Aeronautical Knowledge
bankAngleTarget = constrainf(bankAngleTarget, -DEGREES_TO_RADIANS(60), DEGREES_TO_RADIANS(60)); bankAngleTarget = constrainf(bankAngleTarget, -DEGREES_TO_RADIANS(60), DEGREES_TO_RADIANS(60));
@ -1042,8 +1040,8 @@ static void NOINLINE pidTurnAssistant(pidState_t *pidState, float bankAngleTarge
static void pidApplyFpvCameraAngleMix(pidState_t *pidState, uint8_t fpvCameraAngle) static void pidApplyFpvCameraAngleMix(pidState_t *pidState, uint8_t fpvCameraAngle)
{ {
static uint8_t lastFpvCamAngleDegrees = 0; static uint8_t lastFpvCamAngleDegrees = 0;
static float cosCameraAngle = 1.0; static float cosCameraAngle = 1.0f;
static float sinCameraAngle = 0.0; static float sinCameraAngle = 0.0f;
if (lastFpvCamAngleDegrees != fpvCameraAngle) { if (lastFpvCamAngleDegrees != fpvCameraAngle) {
lastFpvCamAngleDegrees = fpvCameraAngle; lastFpvCamAngleDegrees = fpvCameraAngle;

View file

@ -320,6 +320,13 @@ void servoMixer(float dT)
input[INPUT_RC_CH16] = GET_RX_CHANNEL_INPUT(AUX12); input[INPUT_RC_CH16] = GET_RX_CHANNEL_INPUT(AUX12);
#undef GET_RX_CHANNEL_INPUT #undef GET_RX_CHANNEL_INPUT
#ifdef USE_SIMULATOR
simulatorData.INPUT_STABILIZED_ROLL = input[INPUT_STABILIZED_ROLL];
simulatorData.INPUT_STABILIZED_PITCH = input[INPUT_STABILIZED_PITCH];
simulatorData.INPUT_STABILIZED_YAW = input[INPUT_STABILIZED_YAW];
simulatorData.INPUT_STABILIZED_THROTTLE = input[INPUT_STABILIZED_THROTTLE];
#endif
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
servo[i] = 0; servo[i] = 0;
} }
@ -565,6 +572,11 @@ void processContinuousServoAutotrim(const float dT)
} }
void processServoAutotrim(const float dT) { void processServoAutotrim(const float dT) {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) {
return;
}
#endif
if (feature(FEATURE_FW_AUTOTRIM)) { if (feature(FEATURE_FW_AUTOTRIM)) {
processContinuousServoAutotrim(dT); processContinuousServoAutotrim(dT);
} else { } else {

View file

@ -344,6 +344,14 @@ bool gpsUpdate(void)
return false; return false;
} }
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) {
gpsUpdateTime();
gpsSetState(GPS_RUNNING);
sensorsSet(SENSOR_GPS);
return gpsSol.flags.hasNewData;
}
#endif
#ifdef USE_FAKE_GPS #ifdef USE_FAKE_GPS
return gpsFakeGPSUpdate(); return gpsFakeGPSUpdate();
#else #else

View file

@ -846,6 +846,8 @@ static const char * osdArmingDisabledReasonMessage(void)
FALLTHROUGH; FALLTHROUGH;
case ARMED: case ARMED:
FALLTHROUGH; FALLTHROUGH;
case SIMULATOR_MODE:
FALLTHROUGH;
case WAS_EVER_ARMED: case WAS_EVER_ARMED:
break; break;
} }
@ -2630,11 +2632,12 @@ static bool osdDrawSingleElement(uint8_t item)
case OSD_AIR_SPEED: case OSD_AIR_SPEED:
{ {
#ifdef USE_PITOT #ifdef USE_PITOT
const float airspeed_estimate = getAirspeedEstimate();
buff[0] = SYM_AIR; buff[0] = SYM_AIR;
osdFormatVelocityStr(buff + 1, pitot.airSpeed, false, false); osdFormatVelocityStr(buff + 1, airspeed_estimate, false, false);
if ((osdConfig()->airspeed_alarm_min != 0 && pitot.airSpeed < osdConfig()->airspeed_alarm_min) || if ((osdConfig()->airspeed_alarm_min != 0 && airspeed_estimate < osdConfig()->airspeed_alarm_min) ||
(osdConfig()->airspeed_alarm_max != 0 && pitot.airSpeed > osdConfig()->airspeed_alarm_max)) { (osdConfig()->airspeed_alarm_max != 0 && airspeed_estimate > osdConfig()->airspeed_alarm_max)) {
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
} }
#else #else
@ -3775,14 +3778,16 @@ static void osdUpdateStats(void)
if (feature(FEATURE_GPS)) { if (feature(FEATURE_GPS)) {
value = osdGet3DSpeed(); value = osdGet3DSpeed();
const float airspeed_estimate = getAirspeedEstimate();
if (stats.max_3D_speed < value) if (stats.max_3D_speed < value)
stats.max_3D_speed = value; stats.max_3D_speed = value;
if (stats.max_speed < gpsSol.groundSpeed) if (stats.max_speed < gpsSol.groundSpeed)
stats.max_speed = gpsSol.groundSpeed; stats.max_speed = gpsSol.groundSpeed;
if (stats.max_air_speed < pitot.airSpeed) if (stats.max_air_speed < airspeed_estimate)
stats.max_air_speed = pitot.airSpeed; stats.max_air_speed = airspeed_estimate;
if (stats.max_distance < GPS_distanceToHome) if (stats.max_distance < GPS_distanceToHome)
stats.max_distance = GPS_distanceToHome; stats.max_distance = GPS_distanceToHome;

View file

@ -517,7 +517,7 @@ static int32_t osdCanvasSidebarGetValue(osd_sidebar_scroll_e scroll)
case OSD_SIDEBAR_SCROLL_SPEED: case OSD_SIDEBAR_SCROLL_SPEED:
{ {
#if defined(USE_GPS) #if defined(USE_GPS)
int speed = osdGetSpeedFromSelectedSource(); int16_t speed = osdGetSpeedFromSelectedSource();
switch ((osd_unit_e)osdConfig()->units) { switch ((osd_unit_e)osdConfig()->units) {
case OSD_UNIT_UK: case OSD_UNIT_UK:
FALLTHROUGH; FALLTHROUGH;

View file

@ -53,7 +53,7 @@ PG_RESET_TEMPLATE(osdCommonConfig_t, osdCommonConfig,
.speedSource = SETTING_OSD_SPEED_SOURCE_DEFAULT .speedSource = SETTING_OSD_SPEED_SOURCE_DEFAULT
); );
int osdGetSpeedFromSelectedSource(void) { int16_t osdGetSpeedFromSelectedSource(void) {
int speed = 0; int speed = 0;
switch (osdCommonConfig()->speedSource) { switch (osdCommonConfig()->speedSource) {
case OSD_SPEED_SOURCE_GROUND: case OSD_SPEED_SOURCE_GROUND:
@ -64,7 +64,7 @@ int osdGetSpeedFromSelectedSource(void) {
break; break;
case OSD_SPEED_SOURCE_AIR: case OSD_SPEED_SOURCE_AIR:
#ifdef USE_PITOT #ifdef USE_PITOT
speed = pitot.airSpeed; speed = (int16_t)getAirspeedEstimate();
#endif #endif
break; break;
} }

View file

@ -45,7 +45,7 @@ typedef struct {
PG_DECLARE(osdCommonConfig_t, osdCommonConfig); PG_DECLARE(osdCommonConfig_t, osdCommonConfig);
int osdGetSpeedFromSelectedSource(void); int16_t osdGetSpeedFromSelectedSource(void);
#endif // defined(USE_OSD) || defined(USE_DJI_HD_OSD) #endif // defined(USE_OSD) || defined(USE_DJI_HD_OSD)

View file

@ -537,6 +537,8 @@ static char * osdArmingDisabledReasonMessage(void)
FALLTHROUGH; FALLTHROUGH;
case ARMED: case ARMED:
FALLTHROUGH; FALLTHROUGH;
case SIMULATOR_MODE:
FALLTHROUGH;
case WAS_EVER_ARMED: case WAS_EVER_ARMED:
break; break;
} }
@ -689,7 +691,7 @@ void osdDJIFormatVelocityStr(char* buff)
case OSD_SPEED_SOURCE_AIR: case OSD_SPEED_SOURCE_AIR:
strcpy(sourceBuf, "AIR"); strcpy(sourceBuf, "AIR");
#ifdef USE_PITOT #ifdef USE_PITOT
vel = pitot.airSpeed; vel = getAirspeedEstimate();
#endif #endif
break; break;
} }

View file

@ -100,7 +100,7 @@ static uint8_t serialPortCount;
const uint32_t baudRates[] = { 0, 1200, 2400, 4800, 9600, 19200, 38400, 57600, 115200, 230400, 250000, const uint32_t baudRates[] = { 0, 1200, 2400, 4800, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
460800, 921600, 1000000, 1500000, 2000000, 2470000 }; // see baudRate_e 460800, 921600, 1000000, 1500000, 2000000, 2470000 }; // see baudRate_e
#define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0])) #define BAUD_RATE_COUNT ARRAYLEN(baudRates)
PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 1); PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 1);

View file

@ -53,6 +53,8 @@
#define MSP2_INAV_SET_TEMP_SENSOR_CONFIG 0x201D #define MSP2_INAV_SET_TEMP_SENSOR_CONFIG 0x201D
#define MSP2_INAV_TEMPERATURES 0x201E #define MSP2_INAV_TEMPERATURES 0x201E
#define MSP_SIMULATOR 0x201F
#define MSP2_INAV_SERVO_MIXER 0x2020 #define MSP2_INAV_SERVO_MIXER 0x2020
#define MSP2_INAV_SET_SERVO_MIXER 0x2021 #define MSP2_INAV_SET_SERVO_MIXER 0x2021
#define MSP2_INAV_LOGIC_CONDITIONS 0x2022 #define MSP2_INAV_LOGIC_CONDITIONS 0x2022

View file

@ -203,8 +203,6 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
.launch_max_altitude = SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT, // cm, altitude where to consider launch ended .launch_max_altitude = SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT, // cm, altitude where to consider launch ended
.launch_climb_angle = SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT, // 18 degrees .launch_climb_angle = SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT, // 18 degrees
.launch_max_angle = SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT, // 45 deg .launch_max_angle = SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT, // 45 deg
.launch_manual_throttle = SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_DEFAULT,// OFF
.launch_abort_deadband = SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_DEFAULT, // 100 us
.cruise_yaw_rate = SETTING_NAV_FW_CRUISE_YAW_RATE_DEFAULT, // 20dps .cruise_yaw_rate = SETTING_NAV_FW_CRUISE_YAW_RATE_DEFAULT, // 20dps
.allow_manual_thr_increase = SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_DEFAULT, .allow_manual_thr_increase = SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_DEFAULT,
.useFwNavYawControl = SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT, .useFwNavYawControl = SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT,

View file

@ -660,12 +660,12 @@ bool isFixedWingAutoThrottleManuallyIncreased()
bool isFixedWingFlying(void) bool isFixedWingFlying(void)
{ {
float airspeed = 0; float airspeed = 0.0f;
#ifdef USE_PITOT #ifdef USE_PITOT
airspeed = pitot.airSpeed; airspeed = getAirspeedEstimate();
#endif #endif
bool throttleCondition = getMotorCount() == 0 || rcCommand[THROTTLE] > currentBatteryProfile->nav.fw.cruise_throttle; bool throttleCondition = getMotorCount() == 0 || rcCommand[THROTTLE] > currentBatteryProfile->nav.fw.cruise_throttle;
bool velCondition = posControl.actualState.velXY > 250 || airspeed > 250; bool velCondition = posControl.actualState.velXY > 250.0f || airspeed > 250.0f;
bool launchCondition = isNavLaunchEnabled() && fixedWingLaunchStatus() == FW_LAUNCH_FLYING; bool launchCondition = isNavLaunchEnabled() && fixedWingLaunchStatus() == FW_LAUNCH_FLYING;
return (isImuHeadingValid() && throttleCondition && velCondition) || launchCondition; return (isImuHeadingValid() && throttleCondition && velCondition) || launchCondition;

View file

@ -341,7 +341,7 @@ void updatePositionEstimator_BaroTopic(timeUs_t currentTimeUs)
*/ */
void updatePositionEstimator_PitotTopic(timeUs_t currentTimeUs) void updatePositionEstimator_PitotTopic(timeUs_t currentTimeUs)
{ {
posEstimator.pitot.airspeed = pitot.airSpeed; posEstimator.pitot.airspeed = getAirspeedEstimate();
posEstimator.pitot.lastUpdateTime = currentTimeUs; posEstimator.pitot.lastUpdateTime = currentTimeUs;
} }
#endif #endif
@ -448,6 +448,11 @@ static void updateIMUTopic(timeUs_t currentTimeUs)
/* If calibration is incomplete - report zero acceleration */ /* If calibration is incomplete - report zero acceleration */
if (gravityCalibrationComplete()) { if (gravityCalibrationComplete()) {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) {
posEstimator.imu.calibratedGravityCMSS = GRAVITY_CMSS;
}
#endif
posEstimator.imu.accelNEU.z -= posEstimator.imu.calibratedGravityCMSS; posEstimator.imu.accelNEU.z -= posEstimator.imu.calibratedGravityCMSS;
} }
else { else {

View file

@ -183,6 +183,8 @@ typedef struct {
fpVector3_t accBiasCorr; fpVector3_t accBiasCorr;
} estimationContext_t; } estimationContext_t;
extern navigationPosEstimator_t posEstimator;
extern float updateEPE(const float oldEPE, const float dt, const float newEPE, const float w); extern float updateEPE(const float oldEPE, const float dt, const float newEPE, const float w);
extern void estimationCalculateAGL(estimationContext_t * ctx); extern void estimationCalculateAGL(estimationContext_t * ctx);
extern bool estimationCalculateCorrection_XY_FLOW(estimationContext_t * ctx); extern bool estimationCalculateCorrection_XY_FLOW(estimationContext_t * ctx);

View file

@ -35,6 +35,7 @@
#include "rx/rx.h" #include "rx/rx.h"
#include "common/maths.h" #include "common/maths.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/cli.h"
#include "fc/fc_core.h" #include "fc/fc_core.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
@ -411,7 +412,7 @@ void logicConditionProcess(uint8_t i) {
const int activatorValue = logicConditionGetValue(logicConditions(i)->activatorId); const int activatorValue = logicConditionGetValue(logicConditions(i)->activatorId);
if (logicConditions(i)->enabled && activatorValue) { if (logicConditions(i)->enabled && activatorValue && !cliMode) {
/* /*
* Process condition only when latch flag is not set * Process condition only when latch flag is not set
@ -504,7 +505,7 @@ static int logicConditionGetFlightOperandValue(int operand) {
case LOGIC_CONDITION_OPERAND_FLIGHT_AIR_SPEED: // cm/s case LOGIC_CONDITION_OPERAND_FLIGHT_AIR_SPEED: // cm/s
#ifdef USE_PITOT #ifdef USE_PITOT
return constrain(pitot.airSpeed, 0, INT16_MAX); return constrain(getAirspeedEstimate(), 0, INT16_MAX);
#else #else
return false; return false;
#endif #endif

View file

@ -136,7 +136,7 @@ typedef struct rxConfig_s {
PG_DECLARE(rxConfig_t, rxConfig); PG_DECLARE(rxConfig_t, rxConfig);
#define REMAPPABLE_CHANNEL_COUNT (sizeof(((rxConfig_t *)0)->rcmap) / sizeof(((rxConfig_t *)0)->rcmap[0])) #define REMAPPABLE_CHANNEL_COUNT ARRAYLEN(((rxConfig_t *)0)->rcmap)
typedef struct rxRuntimeConfig_s rxRuntimeConfig_t; typedef struct rxRuntimeConfig_s rxRuntimeConfig_t;
typedef uint16_t (*rcReadRawDataFnPtr)(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data typedef uint16_t (*rcReadRawDataFnPtr)(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data

View file

@ -503,6 +503,13 @@ float accGetMeasuredMaxG(void)
void accUpdate(void) void accUpdate(void)
{ {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) {
//output: acc.accADCf
//unused: acc.dev.ADCRaw[], acc.accClipCount, acc.accVibeSq[]
return;
}
#endif
if (!acc.dev.readFn(&acc.dev)) { if (!acc.dev.readFn(&acc.dev)) {
return; return;
} }

View file

@ -276,7 +276,14 @@ uint32_t baroUpdate(void)
if (baro.dev.start_ut) { if (baro.dev.start_ut) {
baro.dev.start_ut(&baro.dev); baro.dev.start_ut(&baro.dev);
} }
#ifdef USE_SIMULATOR
if (!ARMING_FLAG(SIMULATOR_MODE)) {
//output: baro.baroPressure, baro.baroTemperature
baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature); baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature);
}
#else
baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature);
#endif
state = BAROMETER_NEEDS_SAMPLES; state = BAROMETER_NEEDS_SAMPLES;
return baro.dev.ut_delay; return baro.dev.ut_delay;
break; break;

View file

@ -290,7 +290,16 @@ static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected)
vbat = 0; vbat = 0;
break; break;
} }
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) {
if (simulatorData.flags & SIMU_SIMULATE_BATTERY) {
vbat = ((uint16_t)simulatorData.vbat)*10;
batteryFullVoltage = 1260;
batteryWarningVoltage = 1020;
batteryCriticalVoltage = 960;
}
}
#endif
if (justConnected) { if (justConnected) {
pt1FilterReset(&vbatFilterState, vbat); pt1FilterReset(&vbatFilterState, vbat);
} else { } else {

View file

@ -356,6 +356,12 @@ bool compassIsCalibrationComplete(void)
void compassUpdate(timeUs_t currentTimeUs) void compassUpdate(timeUs_t currentTimeUs)
{ {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) {
magUpdatedAtLeastOnce = 1;
return;
}
#endif
static sensorCalibrationState_t calState; static sensorCalibrationState_t calState;
static timeUs_t calStartedAt = 0; static timeUs_t calStartedAt = 0;
static int16_t magPrev[XYZ_AXIS_COUNT]; static int16_t magPrev[XYZ_AXIS_COUNT];

View file

@ -63,6 +63,11 @@ hardwareSensorStatus_e getHwAccelerometerStatus(void)
hardwareSensorStatus_e getHwCompassStatus(void) hardwareSensorStatus_e getHwCompassStatus(void)
{ {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE) && sensors(SENSOR_MAG)) {
return HW_SENSOR_OK;
}
#endif
#if defined(USE_MAG) #if defined(USE_MAG)
if (detectedSensors[SENSOR_INDEX_MAG] != MAG_NONE) { if (detectedSensors[SENSOR_INDEX_MAG] != MAG_NONE) {
if (compassIsHealthy()) { if (compassIsHealthy()) {

View file

@ -26,7 +26,7 @@
typedef struct { typedef struct {
uint8_t dataAge; uint8_t dataAge;
int8_t temperature; int16_t temperature;
int16_t voltage; int16_t voltage;
int32_t current; int32_t current;
uint32_t rpm; uint32_t rpm;

View file

@ -499,6 +499,13 @@ void FAST_CODE NOINLINE gyroFilter()
void FAST_CODE NOINLINE gyroUpdate() void FAST_CODE NOINLINE gyroUpdate()
{ {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) {
//output: gyro.gyroADCf[axis]
//unused: dev->gyroADCRaw[], dev->gyroZero[];
return;
}
#endif
if (!gyro.initialized) { if (!gyro.initialized) {
return; return;
} }

View file

@ -58,6 +58,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(pitotmeterConfig_t, pitotmeterConfig, PG_PITOTME
#else #else
#define PITOT_HARDWARE_DEFAULT PITOT_NONE #define PITOT_HARDWARE_DEFAULT PITOT_NONE
#endif #endif
PG_RESET_TEMPLATE(pitotmeterConfig_t, pitotmeterConfig, PG_RESET_TEMPLATE(pitotmeterConfig_t, pitotmeterConfig,
.pitot_hardware = SETTING_PITOT_HARDWARE_DEFAULT, .pitot_hardware = SETTING_PITOT_HARDWARE_DEFAULT,
.pitot_lpf_milli_hz = SETTING_PITOT_LPF_MILLI_HZ_DEFAULT, .pitot_lpf_milli_hz = SETTING_PITOT_LPF_MILLI_HZ_DEFAULT,
@ -205,6 +206,11 @@ STATIC_PROTOTHREAD(pitotThread)
} }
pitot.dev.calculate(&pitot.dev, &pitotPressureTmp, NULL); pitot.dev.calculate(&pitot.dev, &pitotPressureTmp, NULL);
#ifdef USE_SIMULATOR
if (simulatorData.flags & SIMU_AIRSPEED) {
pitotPressureTmp = sq(simulatorData.airSpeed) * SSL_AIR_DENSITY / 20000.0f + SSL_AIR_PRESSURE;
}
#endif
ptYield(); ptYield();
// Filter pressure // Filter pressure
@ -226,8 +232,13 @@ STATIC_PROTOTHREAD(pitotThread)
pitot.airSpeed = pitotmeterConfig()->pitot_scale * fast_fsqrtf(2.0f * fabsf(pitot.pressure - pitot.pressureZero) / SSL_AIR_DENSITY) * 100; pitot.airSpeed = pitotmeterConfig()->pitot_scale * fast_fsqrtf(2.0f * fabsf(pitot.pressure - pitot.pressureZero) / SSL_AIR_DENSITY) * 100;
} else { } else {
performPitotCalibrationCycle(); performPitotCalibrationCycle();
pitot.airSpeed = 0; pitot.airSpeed = 0.0f;
} }
#ifdef USE_SIMULATOR
if (simulatorData.flags & SIMU_AIRSPEED) {
pitot.airSpeed = simulatorData.airSpeed;
}
#endif
} }
ptEnd(0); ptEnd(0);
@ -238,7 +249,7 @@ void pitotUpdate(void)
pitotThread(); pitotThread();
} }
int32_t pitotCalculateAirSpeed(void) float getAirspeedEstimate(void)
{ {
return pitot.airSpeed; return pitot.airSpeed;
} }

View file

@ -65,7 +65,7 @@ bool pitotInit(void);
bool pitotIsCalibrationComplete(void); bool pitotIsCalibrationComplete(void);
void pitotStartCalibration(void); void pitotStartCalibration(void);
void pitotUpdate(void); void pitotUpdate(void);
int32_t pitotCalculateAirSpeed(void); float getAirspeedEstimate(void);
bool pitotIsHealthy(void); bool pitotIsHealthy(void);
#endif #endif

View file

@ -0,0 +1 @@
target_stm32f405xg(ATOMRCF405NAVI)

View file

@ -0,0 +1,49 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute and/or modify
* it under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
*/
#include <stdint.h>
#include "platform.h"
#include "drivers/bus.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/pinio.h"
#include "drivers/sensor.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8
DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED_STRIP
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,197 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute and/or modify
* it under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "ATF4"
#define USBD_PRODUCT_STRING "AtomRCF405NAVI"
#define LED0 PA13
#define LED1 PA14
#define BEEPER PC5
#define BEEPER_INVERTED
/*
* SPI defines
*/
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
/*
* I2C defines
*/
#define USE_I2C
#define DEFAULT_I2C_BUS BUS_I2C1
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9
/*
* Gyroscope
*/
#define USE_EXTI
#define GYRO_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
//BMI270
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW180_DEG
#define BMI270_SPI_BUS BUS_SPI1
#define BMI270_CS_PIN PA4
#define BMI270_EXTI_PIN GYRO_INT_EXTI
/*
* Magnetometer
*/
#define USE_MAG
#define MAG_I2C_BUS DEFAULT_I2C_BUS
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
/*
* Barometer
*/
#define USE_BARO
#define BARO_I2C_BUS DEFAULT_I2C_BUS
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define USE_BARO_DPS310
#define USE_BARO_SPL06
/*
* Serial ports
*/
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_UART4
#define USE_UART5
#define USE_UART6
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PC10
#define UART3_RX_PIN PC11
#define UART4_TX_PIN PA0
#define UART4_RX_PIN PA1
#define UART5_TX_PIN PC12
#define UART5_RX_PIN PD2
#define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7
#define SERIAL_PORT_COUNT 7
/*
* ADC
*/
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC1_DMA_STREAM DMA2_Stream0
#define ADC_CHANNEL_1_PIN PC0
#define ADC_CHANNEL_2_PIN PC1
#define ADC_CHANNEL_3_PIN PC2
#define VBAT_ADC_CHANNEL ADC_CHN_3
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_1
/*
* OSD
*/
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
/*
* SD Card
*/
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_SPI_BUS BUS_SPI3
#define SDCARD_CS_PIN PB6
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
/*
* LED Strip
*/
#define USE_LED_STRIP
#define WS2811_PIN PB7
/*
* Other configs
*/
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT )
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define USE_OPFLOW
#define USE_OPFLOW_MSP
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS
#define PITOT_I2C_BUS DEFAULT_I2C_BUS
#define USE_DSHOT
#define USE_ESC_SENSOR
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define MAX_PWM_OUTPUT_PORTS 8
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))

View file

@ -0,0 +1 @@
target_stm32f722xe(IFLIGHT_BLITZ_F7_PRO)

View file

@ -0,0 +1,47 @@
/*
* This file is part of INAV Project.
*
* INAV Project is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV Project is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV Project. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "drivers/bus.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/pinio.h"
#include "drivers/sensor.h"
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, BMI270_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3
DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8
DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), // LED
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,157 @@
/*
* This file is part of INAV Project.
*
* INAV Project is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV Project is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV Project. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "IFBLITZF7PRO"
#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_F7_PRO"
#define LED0 PC4
#define BEEPER PC15
#define BEEPER_INVERTED
// *************** IMU generic ***********************
#define USE_DUAL_GYRO
#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
// *************** Gyro & ACC **********************
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW270_DEG
#define MPU6000_SPI_BUS BUS_SPI1
#define MPU6000_CS_PIN PA15
#define MPU6000_EXTI_PIN PA8
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW0_DEG_FLIP
#define BMI270_SPI_BUS BUS_SPI1
#define BMI270_CS_PIN PA15
#define BMI270_EXTI_PIN PA8
// *************** I2C/Baro/Mag *********************
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C2_SCL PB10 // SCL pad
#define I2C2_SDA PB11 // SDA pad
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_BMP280
#define USE_BARO_DPS310
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#define TEMPERATURE_I2C_BUS BUS_I2C2
#define PITOT_I2C_BUS BUS_I2C2
// *************** SD Card **************************
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_SPI_BUS BUS_SPI3
#define SDCARD_CS_PIN PB9
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
// *************** OSD *****************************
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
// *************** UART *****************************
#define USE_VCP
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART4
#define UART4_RX_PIN PC11
#define UART4_TX_PIN PC10
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN PC12
#define SERIAL_PORT_COUNT 5
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_CRSF
#define SERIALRX_UART SERIAL_PORT_USART2
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC1_DMA_STREAM DMA2_Stream0
#define ADC_CHANNEL_1_PIN PC1
#define ADC_CHANNEL_2_PIN PC2
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define CURRENT_METER_SCALE 65
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS BUS_I2C2
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD)
#define USE_LED_STRIP
#define WS2811_PIN PA1 // TIM2_CH2
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define MAX_PWM_OUTPUT_PORTS 8
#define USE_DSHOT
#define USE_ESC_SENSOR
#define BNO055_I2C_BUS BUS_I2C2

View file

@ -0,0 +1 @@
target_stm32f722xe(IFLIGHT_JBF7PRO)

View file

@ -0,0 +1,29 @@
/*
* This file is part of INAV Project.
*
* INAV Project is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV Project is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV Project. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "fc/fc_msp_box.h"
#include "io/piniobox.h"
void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
}

View file

@ -0,0 +1,42 @@
/*
* This file is part of INAV Project.
*
* INAV Project is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV Project is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV Project. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "drivers/bus.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S8
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,169 @@
/*
* This file is part of INAV Project.
*
* INAV Project is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV Project is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV Project. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "IFJBF7"
#define USBD_PRODUCT_STRING "IFLIGHT_JBF7PRO"
#define LED0 PC15
#define BEEPER PC13
#define BEEPER_INVERTED
// *************** IMU generic ***********************
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
// *************** Gyro & ACC **********************
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW0_DEG
#define MPU6000_SPI_BUS BUS_SPI1
#define MPU6000_CS_PIN PA4
#define MPU6000_EXTI_PIN PC4
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW0_DEG
#define BMI270_SPI_BUS BUS_SPI1
#define BMI270_CS_PIN PA4
#define BMI270_EXTI_PIN PC4
// *************** I2C/Baro/Mag *********************
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8 // SCL pad
#define I2C1_SDA PB9 // SDA pad
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_BMP280
#define USE_BARO_DPS310
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#define TEMPERATURE_I2C_BUS BUS_I2C1
#define PITOT_I2C_BUS BUS_I2C1
// *************** SD Card **************************
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_SPI_BUS BUS_SPI3
#define SDCARD_CS_PIN PA15
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
// *************** OSD *****************************
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PC3
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
// *************** PINIO ***************************
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PC0
// *************** UART *****************************
#define USE_VCP
#define VBUS_SENSING_PIN PB2
#define VBUS_SENSING_ENABLED
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PC11
#define UART3_TX_PIN PC10
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN PC12
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN NONE
#define SERIAL_PORT_COUNT 7
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC1_DMA_STREAM DMA2_Stream0
#define ADC_CHANNEL_1_PIN PC2
#define ADC_CHANNEL_2_PIN PC1
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS BUS_I2C1
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD)
#define USE_LED_STRIP
#define WS2811_PIN PA8 // TIM2_CH1
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define MAX_PWM_OUTPUT_PORTS 8
#define USE_DSHOT
#define USE_ESC_SENSOR
#define BNO055_I2C_BUS BUS_I2C1

View file

@ -1 +1,2 @@
target_stm32f405xg(MATEKF405SE) target_stm32f405xg(MATEKF405SE)
target_stm32f405xg(MATEKF405SE_PINIO)

View file

@ -14,3 +14,6 @@
* 2x I2C * 2x I2C
* 2x Motors & 7x Servos * 2x Motors & 7x Servos
* 4x BEC + current sensor * 4x BEC + current sensor
### MATEKF405SE_PINIO
Replaces UART 6 Tx with USER 1 for PINIO

View file

@ -17,15 +17,24 @@
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#include "config/config_master.h" #include "config/config_master.h"
#include "config/feature.h" #include "config/feature.h"
#include "flight/mixer.h" #include "flight/mixer.h"
#include "io/serial.h" #include "io/serial.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
#include "fc/fc_msp_box.h"
#include "io/piniobox.h"
// alternative defaults settings for MATEKF405SE targets // alternative defaults settings for MATEKF405SE targets
void targetConfiguration(void) void targetConfiguration(void)
{ {
#ifdef MATEKF405SE_PINIO
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
#endif
serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP;
serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600; serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600;

View file

@ -20,8 +20,11 @@
#define TARGET_BOARD_IDENTIFIER "MF4S" #define TARGET_BOARD_IDENTIFIER "MF4S"
#define USBD_PRODUCT_STRING "Matek_F405SE" #define USBD_PRODUCT_STRING "Matek_F405SE"
// ******** Board LEDs **********************
#define LED0 PA14 //Blue #define LED0 PA14 //Blue
#define LED1 PA13 //Green #define LED1 PA13 //Green
// ******* Beeper ***********
#define BEEPER PC15 #define BEEPER PC15
#define BEEPER_INVERTED #define BEEPER_INVERTED
@ -33,6 +36,7 @@
#define SPI1_MISO_PIN PA6 #define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7 #define SPI1_MOSI_PIN PA7
// MPU6000
#define USE_IMU_MPU6000 #define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW270_DEG #define IMU_MPU6000_ALIGN CW270_DEG
#define MPU6000_CS_PIN PA4 #define MPU6000_CS_PIN PA4
@ -43,7 +47,7 @@
#define USE_MPU_DATA_READY_SIGNAL #define USE_MPU_DATA_READY_SIGNAL
// *************** I2C /Baro/Mag ********************* // *************** I2C/Baro/Mag *********************
#define USE_I2C #define USE_I2C
#define USE_I2C_DEVICE_1 #define USE_I2C_DEVICE_1
#define I2C1_SCL PB8 #define I2C1_SCL PB8
@ -126,9 +130,11 @@
#define UART5_TX_PIN PC12 #define UART5_TX_PIN PC12
#define UART5_RX_PIN PD2 #define UART5_RX_PIN PD2
#ifndef MATEKF405SE_PINIO
#define USE_UART6 #define USE_UART6
#define UART6_TX_PIN PC6 #define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7 #define UART6_RX_PIN PC7
#endif
#define USE_SOFTSERIAL1 //Frsky SmartPort on TX2 pad #define USE_SOFTSERIAL1 //Frsky SmartPort on TX2 pad
#define SOFTSERIAL_1_TX_PIN PA2 #define SOFTSERIAL_1_TX_PIN PA2
@ -158,6 +164,13 @@
#define WS2811_DMA_STREAM DMA1_Stream5 #define WS2811_DMA_STREAM DMA1_Stream5
#define WS2811_DMA_CHANNEL DMA_Channel_3 #define WS2811_DMA_CHANNEL DMA_Channel_3
// *************** PINIO ***************************
#ifdef MATEKF405SE_PINIO
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PC6 // USER 1
#endif
// *************** OTHERS ************************* // *************** OTHERS *************************
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL) #define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL)
#define CURRENT_METER_SCALE 317 #define CURRENT_METER_SCALE 317
@ -167,7 +180,6 @@
#define USE_DSHOT #define USE_DSHOT
#define USE_ESC_SENSOR #define USE_ESC_SENSOR
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTA 0xffff

View file

@ -0,0 +1 @@
target_stm32f722xe(SPEEDYBEEF7V3)

View file

@ -0,0 +1,34 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "fc/fc_msp_box.h"
#include "io/serial.h"
void targetConfiguration(void)
{
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_ESCSERIAL;
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
}

View file

@ -0,0 +1,49 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "drivers/bus.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/pinio.h"
#include "drivers/sensor.h"
BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, BMI270_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN);
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 Clash with S2, DSHOT does not work
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8
DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED
DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), // Camera Control
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,176 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "SB73"
#define USBD_PRODUCT_STRING "SpeedyBeeF7V3"
#define LED0 PA14
#define LED1 PA15
#define USE_BEEPER
#define BEEPER PC13
#define BEEPER_INVERTED
// *************** UART *****************************
#define USB_IO
#define USE_VCP
// #define VBUS_SENSING_PIN PC15
// #define VBUS_SENSING_ENABLED
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PC9
#define PINIO1_FLAGS PINIO_FLAGS_INVERTED
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN NONE
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 6
// *************** Gyro & ACC **********************
#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW270_DEG_FLIP
#define MPU6000_SPI_BUS BUS_SPI1
#define MPU6000_CS_PIN PB2
#define MPU6000_EXTI_PIN PC4
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW0_DEG_FLIP
#define BMI270_SPI_BUS BUS_SPI1
#define BMI270_CS_PIN PC15
#define BMI270_EXTI_PIN PC3
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
// *************** I2C(Baro & I2C) **************************
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9
// Baro
#define USE_BARO
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_DPS310
#define USE_BARO_SPL06
#define BARO_I2C_BUS BUS_I2C1
// Mag
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
// *************** Internal SD card **************************
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_SPI_BUS BUS_SPI3
#define SDCARD_CS_PIN PD2
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
// *************** OSD *****************************
#define USE_OSD
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
// *************** ADC *****************************
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC2
#define ADC_CHANNEL_2_PIN PC0
#define ADC_CHANNEL_3_PIN PC1
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
#define RSSI_ADC_CHANNEL ADC_CHN_2
// *************** LED *****************************
#define USE_LED_STRIP
#define WS2811_PIN PC8
// ********** Optiical Flow adn Lidar **************
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define USE_OPFLOW
#define USE_OPFLOW_MSP
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX)
#define USE_DSHOT
#define USE_ESC_SENSOR
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define SERIALRX_UART SERIAL_PORT_USART2
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define MAX_PWM_OUTPUT_PORTS 8
#define CURRENT_METER_SCALE 490
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))

View file

@ -184,6 +184,8 @@
// Wind estimator // Wind estimator
#define USE_WIND_ESTIMATOR #define USE_WIND_ESTIMATOR
#define USE_SIMULATOR
//Designed to free space of F722 and F411 MCUs //Designed to free space of F722 and F411 MCUs
#if (MCU_FLASH_SIZE > 512) #if (MCU_FLASH_SIZE > 512)

View file

@ -169,7 +169,7 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
return sendIbusMeasurement2(address, (uint16_t) (attitude.values.roll * 10)); //in ddeg -> cdeg, 1ddeg = 10cdeg return sendIbusMeasurement2(address, (uint16_t) (attitude.values.roll * 10)); //in ddeg -> cdeg, 1ddeg = 10cdeg
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_VSPEED) { //Speed cm/s } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_VSPEED) { //Speed cm/s
#ifdef USE_PITOT #ifdef USE_PITOT
if (sensors(SENSOR_PITOT)) return sendIbusMeasurement2(address, (uint16_t) (pitot.airSpeed)); //int32_t if (sensors(SENSOR_PITOT)) return sendIbusMeasurement2(address, (uint16_t)getAirspeedEstimate()); //int32_t
else else
#endif #endif
return sendIbusMeasurement2(address, 0); return sendIbusMeasurement2(address, 0);

View file

@ -189,7 +189,7 @@ void ltm_sframe(sbuf_t *dst)
sbufWriteU16(dst, (uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // current mAh (65535 mAh max) sbufWriteU16(dst, (uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // current mAh (65535 mAh max)
sbufWriteU8(dst, (uint8_t)((getRSSI() * 254) / 1023)); // scaled RSSI (uchar) sbufWriteU8(dst, (uint8_t)((getRSSI() * 254) / 1023)); // scaled RSSI (uchar)
#if defined(USE_PITOT) #if defined(USE_PITOT)
sbufWriteU8(dst, sensors(SENSOR_PITOT) ? pitot.airSpeed / 100.0f : 0); // in m/s sbufWriteU8(dst, sensors(SENSOR_PITOT) ? getAirspeedEstimate() / 100.0f : 0); // in m/s
#else #else
sbufWriteU8(dst, 0); sbufWriteU8(dst, 0);
#endif #endif

View file

@ -645,7 +645,7 @@ void mavlinkSendHUDAndHeartbeat(void)
#if defined(USE_PITOT) #if defined(USE_PITOT)
if (sensors(SENSOR_PITOT)) { if (sensors(SENSOR_PITOT)) {
mavAirSpeed = pitot.airSpeed / 100.0f; mavAirSpeed = getAirspeedEstimate() / 100.0f;
} }
#endif #endif

View file

@ -551,7 +551,7 @@ void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clear
case FSSP_DATAID_ASPD : case FSSP_DATAID_ASPD :
#ifdef USE_PITOT #ifdef USE_PITOT
if (sensors(SENSOR_PITOT)) { if (sensors(SENSOR_PITOT)) {
smartPortSendPackage(id, pitot.airSpeed * 0.194384449f); // cm/s to knots*1 smartPortSendPackage(id, getAirspeedEstimate() * 0.194384449f); // cm/s to knots*1
*clearToSend = false; *clearToSend = false;
} }
#endif #endif