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

Merge branch 'master' into dzikuvx-sqrtf-update

This commit is contained in:
Pawel Spychalski (DzikuVx) 2021-06-13 14:55:09 +02:00
commit f737fe1901
53 changed files with 6612 additions and 940 deletions

1
.gitignore vendored
View file

@ -8,6 +8,7 @@
.project
.settings
.cproject
.cache/
__pycache__
startup_stm32f10x_md_gcc.s
.vagrant/

View file

@ -35,6 +35,7 @@ Gaël James
Gregor Ottmann
Google LLC
Hyon Lim
Hubert Jozwiak
James Harrison
Jan Staal
Jeremy Waters

View file

@ -143,9 +143,9 @@ main_sources(STM32H7_SRC
config/config_streamer_stm32h7.c
# drivers/adc_stm32h7xx.c
drivers/adc_stm32h7xx.c
drivers/bus_i2c_hal.c
# drivers/dma_stm32h7xx.c
drivers/dma_stm32h7xx.c
drivers/bus_spi_hal.c
drivers/memprot.h
drivers/memprot_hal.c

View file

@ -81,7 +81,7 @@ IPF can be edited using INAV Configurator user interface, of via CLI
| Operand Type | Name | Notes |
|---- |---- |---- |
| 0 | VALUE | Value derived from `value` field |
| 1 | RC_CHANNEL | `value` points to RC channel number, indexed from 1 |
| 1 | GET_RC_CHANNEL | `value` points to RC channel number, indexed from 1 |
| 2 | FLIGHT | `value` points to flight parameter table |
| 3 | FLIGHT_MODE | `value` points to flight modes table |
| 4 | LC | `value` points to other logic condition ID |

File diff suppressed because it is too large Load diff

View file

@ -3,11 +3,13 @@
This is a guide on how to use Windows MSYS2 distribution and building platform to build iNav firmware. This environment is very simple to manage and does not require installing docker for Windows which may get in the way of VMWare or any other virtualization software you already have running for other reasons. Another benefit of this approach is that the compiler runs natively on Windows, so performance is much better than compiling in a virtual environment or a container. You can also integrate with whatever IDE you are using to make code edits and work with github, which makes the entire development and testing workflow a lot more efficient. In addition to MSYS2, this build environment also uses Arm Embedded GCC tolkit from The xPack Project, which provides many benefits over the toolkits maintained by arm.com
Some of those benefits are described here:
https://xpack.github.io/arm-none-eabi-gcc/
## Setting up build environment
Download MSYS2 for your architecture (most likely 64-bit)
https://www.msys2.org/wiki/MSYS2-installation/
Click on 64-bit, scroll all the way down for the latest release
@ -23,14 +25,14 @@ Once MSYS2 is installed, you can open up a new terminal window by running:
You can also make a shortcut of this somewhere on your taskbar, desktop, etc, or even setup a shortcut key to open it up every time you need to get a terminal window. If you right click on the window you can customize the font and layout to make it more comfortable to work with. This is very similar to cygwin or any other terminal program you might have used before
This is the best part:
`
```
pacman -S git ruby make cmake gcc mingw-w64-x86_64-libwinpthread-git unzip wget
`
```
Now, each release needs a different version of arm toolchain. To setup the xPack ARM toolchain, use the following process:
First, get the release you want to build or master if you want the latest/greatest
`
First, setup your work path, get the release you want to build or master if you want the latest/greatest
```
mkdir /c/Workspace
cd /c/Workspace
# you can also check out your own fork here which makes contributing easier
@ -39,28 +41,40 @@ cd inav
# switch to release you want or skip next 2 lines if you want latest
git fetch origin
git checkout -b release_2.6.1 origin/release_2.6.1
```
Now create the build and xpack directories and get the toolkit version you need for your inav version
```
mkdir build
cd build
mkdir /c/Workspace/xpack
cd /c/Workspace/xpack
# now find the arm toolchain version you need for this inav release
cat /c/Workspace/inav/cmake/arm-none-eabi-checks.cmake | grep "set(arm_none_eabi_gcc_version" | cut -d\" -f2
# this will give you the version you need for any given release or master branch
# you can get to all the releases here and find the version you need
# https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/
```
This will give you the version you need for any given release or master branch. You can get to all the releases here and find the version you need
https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/
```
# for version 2.6.1, version needed is 9.2.1
wget https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/download/v9.2.1-1.1/xpack-arm-none-eabi-gcc-9.2.1-1.1-win32-x64.zip
unzip xpack-arm-none-eabi-gcc-9.2.1-1.1-win32-x64.zip
# this is important, put the toolkit first before your path so that it is
# picked up ahead of any other versions that may be present on your system
```
This is important, put the toolkit first before your path so that it is picked up ahead of any other versions that may be present on your system
```
export PATH=/c/Workspace/xpack/xpack-arm-none-eabi-gcc-9.2.1-1.1/bin:$PATH
cd /c/Workspace/inav/build
# you may need to run rm -rf * in build directory if you had any failed previous runs
# now run cmake .. while inside the build directory
```
You may need to run rm -rf * in build directory if you had any failed previous runs now run cmake
```
# while inside the build directory
cmake ..
# once that's done you can compile the firmware for your controller
```
Once that's done you can compile the firmware for your controller
```
make DALRCF405
# the generated hex file will be in /c/Workspace/inav/build folder
`
```
To get a list of available targets in iNav, see the target src folder
https://github.com/tednv/inav/tree/master/src/main/target
The generated hex file will be in /c/Workspace/inav/build folder
At the time of writting this document, I believe this is the fastest, easiest, and most efficient Windows build environment that is available. I have used this approach several years ago and was very happy with it building iNav 2.1 and 2.2, and now I'm getting back into it so figured I would share my method

View file

@ -98,7 +98,7 @@ void gyroIntExtiInit(gyroDev_t *gyro)
}
#endif
#if defined (STM32F7)
#if defined (STM32F7) || defined (STM32H7)
IOInit(gyro->busDev->irqPin, OWNER_MPU, RESOURCE_EXTI, 0);
EXTIHandlerInit(&gyro->exti, gyroIntExtiHandler);

View file

@ -55,9 +55,9 @@ static uint8_t activeChannelCount[ADCDEV_COUNT] = {0};
static int adcFunctionMap[ADC_FUNCTION_COUNT];
adc_config_t adcConfig[ADC_CHN_COUNT]; // index 0 is dummy for ADC_CHN_NONE
volatile uint16_t adcValues[ADCDEV_COUNT][ADC_CHN_COUNT * ADC_AVERAGE_N_SAMPLES];
volatile ADC_VALUES_ALIGNMENT(uint16_t adcValues[ADCDEV_COUNT][ADC_CHN_COUNT * ADC_AVERAGE_N_SAMPLES]);
uint8_t adcChannelByTag(ioTag_t ioTag)
uint32_t adcChannelByTag(ioTag_t ioTag)
{
for (uint8_t i = 0; i < ARRAYLEN(adcTagMap); i++) {
if (ioTag == adcTagMap[i].tag)

View file

@ -22,19 +22,27 @@
#if defined(STM32F4) || defined(STM32F7)
#define ADC_TAG_MAP_COUNT 16
#elif defined(STM32H7)
#define ADC_TAG_MAP_COUNT 28
#elif defined(STM32F3)
#define ADC_TAG_MAP_COUNT 39
#else
#define ADC_TAG_MAP_COUNT 10
#endif
#if defined(STM32H7)
#define ADC_VALUES_ALIGNMENT(def) __attribute__ ((section(".DMA_RAM"))) def __attribute__ ((aligned (32)))
#else
#define ADC_VALUES_ALIGNMENT(def) def
#endif
typedef enum ADCDevice {
ADCINVALID = -1,
ADCDEV_1 = 0,
#if defined(STM32F3)
ADCDEV_2,
ADCDEV_MAX = ADCDEV_2,
#elif defined(STM32F4) || defined(STM32F7)
#elif defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
ADCDEV_2,
ADCDEV_3,
ADCDEV_MAX = ADCDEV_3,
@ -46,20 +54,20 @@ typedef enum ADCDevice {
typedef struct adcTagMap_s {
ioTag_t tag;
uint8_t channel;
uint32_t channel;
} adcTagMap_t;
typedef struct adcDevice_s {
ADC_TypeDef* ADCx;
rccPeriphTag_t rccADC;
rccPeriphTag_t rccDMA;
#if defined(STM32F4) || defined(STM32F7)
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
DMA_Stream_TypeDef* DMAy_Streamx;
uint32_t channel;
#else
DMA_Channel_TypeDef* DMAy_Channelx;
#endif
#if defined(STM32F7)
#if defined(STM32F7) || defined(STM32H7)
ADC_HandleTypeDef ADCHandle;
DMA_HandleTypeDef DmaHandle;
#endif
@ -70,7 +78,7 @@ typedef struct adcDevice_s {
typedef struct adc_config_s {
ioTag_t tag;
ADCDevice adcDevice;
uint8_t adcChannel; // ADC1_INxx channel number
uint32_t adcChannel; // ADC1_INxx channel number
uint8_t dmaIndex; // index into DMA buffer in case of sparse channels
bool enabled;
uint8_t sampleTime;
@ -78,8 +86,8 @@ typedef struct adc_config_s {
extern const adcTagMap_t adcTagMap[ADC_TAG_MAP_COUNT];
extern adc_config_t adcConfig[ADC_CHN_COUNT];
extern volatile uint16_t adcValues[ADCDEV_COUNT][ADC_CHN_COUNT * ADC_AVERAGE_N_SAMPLES];
extern volatile ADC_VALUES_ALIGNMENT(uint16_t adcValues[ADCDEV_COUNT][ADC_CHN_COUNT * ADC_AVERAGE_N_SAMPLES]);
void adcHardwareInit(drv_adc_config_t *init);
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance);
uint8_t adcChannelByTag(ioTag_t ioTag);
uint32_t adcChannelByTag(ioTag_t ioTag);

View file

@ -0,0 +1,230 @@
/*
* 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 <string.h>
#include "platform.h"
#include "build/debug.h"
#include "platform.h"
#include "drivers/time.h"
#include "drivers/io.h"
#include "io_impl.h"
#include "rcc.h"
#include "dma.h"
#include "drivers/sensor.h"
#include "drivers/accgyro/accgyro.h"
#include "adc.h"
#include "adc_impl.h"
static adcDevice_t adcHardware[ADCDEV_COUNT] = {
{
.ADCx = ADC1,
.rccADC = RCC_AHB1(ADC12),
.rccDMA = RCC_AHB1(DMA2),
.DMAy_Streamx = DMA2_Stream0,
.channel = DMA_REQUEST_ADC1,
.enabled = false,
.usedChannelCount = 0
},
/* currently not used
{
.ADCx = ADC2,
.rccADC = RCC_AHB1(ADC12),
.rccDMA = RCC_AHB1(DMA2),
.DMAy_Streamx = DMA2_Stream1,
.channel = DMA_REQUEST_ADC2,
.enabled = false,
.usedChannelCount = 0
}
*/
};
adcDevice_t adcDevice[ADCDEV_COUNT];
/* note these could be packed up for saving space */
const adcTagMap_t adcTagMap[] = {
{ DEFIO_TAG_E__PC0, ADC_CHANNEL_10 },
{ DEFIO_TAG_E__PC1, ADC_CHANNEL_11 },
{ DEFIO_TAG_E__PC2, ADC_CHANNEL_0 },
{ DEFIO_TAG_E__PC3, ADC_CHANNEL_1 },
{ DEFIO_TAG_E__PC4, ADC_CHANNEL_4 },
{ DEFIO_TAG_E__PC5, ADC_CHANNEL_8 },
{ DEFIO_TAG_E__PB0, ADC_CHANNEL_9 },
{ DEFIO_TAG_E__PB1, ADC_CHANNEL_5 },
{ DEFIO_TAG_E__PA0, ADC_CHANNEL_16 },
{ DEFIO_TAG_E__PA1, ADC_CHANNEL_17 },
{ DEFIO_TAG_E__PA2, ADC_CHANNEL_14 },
{ DEFIO_TAG_E__PA3, ADC_CHANNEL_15 },
{ DEFIO_TAG_E__PA4, ADC_CHANNEL_18 },
{ DEFIO_TAG_E__PA5, ADC_CHANNEL_19 },
{ DEFIO_TAG_E__PA6, ADC_CHANNEL_3 },
{ DEFIO_TAG_E__PA7, ADC_CHANNEL_7 },
};
// Translate rank number x to ADC_REGULAR_RANK_x (Note that array index is 0-origin)
static const uint32_t adcRegularRankMap[] = {
ADC_REGULAR_RANK_1,
ADC_REGULAR_RANK_2,
ADC_REGULAR_RANK_3,
ADC_REGULAR_RANK_4,
ADC_REGULAR_RANK_5,
ADC_REGULAR_RANK_6,
ADC_REGULAR_RANK_7,
ADC_REGULAR_RANK_8,
ADC_REGULAR_RANK_9,
ADC_REGULAR_RANK_10,
ADC_REGULAR_RANK_11,
ADC_REGULAR_RANK_12,
ADC_REGULAR_RANK_13,
ADC_REGULAR_RANK_14,
ADC_REGULAR_RANK_15,
ADC_REGULAR_RANK_16,
};
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
{
if (instance == ADC1)
return ADCDEV_1;
if (instance == ADC2)
return ADCDEV_2;
return ADCINVALID;
}
static void adcInstanceInit(ADCDevice adcDevice)
{
adcDevice_t * adc = &adcHardware[adcDevice];
RCC_ClockCmd(adc->rccDMA, ENABLE);
RCC_ClockCmd(adc->rccADC, ENABLE);
adc->ADCHandle.Instance = adc->ADCx;
adc->ADCHandle.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
adc->ADCHandle.Init.Resolution = ADC_RESOLUTION_12B;
adc->ADCHandle.Init.ContinuousConvMode = ENABLE;
adc->ADCHandle.Init.ExternalTrigConv = ADC_EXTERNALTRIG_T1_CC1;
adc->ADCHandle.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
adc->ADCHandle.Init.NbrOfConversion = adc->usedChannelCount;
adc->ADCHandle.Init.ScanConvMode = adc->usedChannelCount > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group
adc->ADCHandle.Init.DiscontinuousConvMode = DISABLE;
adc->ADCHandle.Init.NbrOfDiscConversion = 0;
adc->ADCHandle.Init.EOCSelection = DISABLE;
adc->ADCHandle.Init.LowPowerAutoWait = DISABLE;
// Enable circular DMA.
adc->ADCHandle.Init.ConversionDataManagement = ADC_CONVERSIONDATA_DMA_CIRCULAR;
adc->ADCHandle.Init.Overrun = ADC_OVR_DATA_OVERWRITTEN;
adc->ADCHandle.Init.OversamplingMode = DISABLE;
if (HAL_ADC_Init(&adc->ADCHandle) != HAL_OK) {
return;
}
if (HAL_ADCEx_Calibration_Start(&adc->ADCHandle, ADC_CALIB_OFFSET, ADC_SINGLE_ENDED) != HAL_OK) {
return;
}
adc->DmaHandle.Init.Request = adc->channel;
adc->DmaHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
adc->DmaHandle.Init.PeriphInc = DMA_PINC_DISABLE;
adc->DmaHandle.Init.MemInc = ((adc->usedChannelCount > 1) || (ADC_AVERAGE_N_SAMPLES > 1)) ? DMA_MINC_ENABLE : DMA_MINC_DISABLE;
adc->DmaHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
adc->DmaHandle.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
adc->DmaHandle.Init.Mode = DMA_CIRCULAR;
adc->DmaHandle.Init.Priority = DMA_PRIORITY_HIGH;
adc->DmaHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
adc->DmaHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
adc->DmaHandle.Init.MemBurst = DMA_MBURST_SINGLE;
adc->DmaHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
adc->DmaHandle.Instance = adc->DMAy_Streamx;
if (HAL_DMA_Init(&adc->DmaHandle) != HAL_OK) {
return;
}
__HAL_LINKDMA(&adc->ADCHandle, DMA_Handle, adc->DmaHandle);
uint8_t rank = 0;
for (int i = ADC_CHN_1; i < ADC_CHN_COUNT; i++) {
if (!adcConfig[i].enabled || adcConfig[i].adcDevice != adcDevice) {
continue;
}
ADC_ChannelConfTypeDef sConfig;
sConfig.Channel = adcConfig[i].adcChannel;
sConfig.Rank = adcRegularRankMap[rank++];
sConfig.SamplingTime = adcConfig[i].sampleTime;
sConfig.SingleDiff = ADC_SINGLE_ENDED;
sConfig.OffsetNumber = ADC_OFFSET_NONE;
sConfig.Offset = 0;
if (HAL_ADC_ConfigChannel(&adc->ADCHandle, &sConfig) != HAL_OK) {
return;
}
}
if (HAL_ADC_Start_DMA(&adc->ADCHandle, (uint32_t*)&adcValues[adcDevice], adc->usedChannelCount * ADC_AVERAGE_N_SAMPLES) != HAL_OK) {
return;
}
}
void adcHardwareInit(drv_adc_config_t *init)
{
UNUSED(init);
int configuredAdcChannels = 0;
for (int i = ADC_CHN_1; i < ADC_CHN_COUNT; i++) {
if (!adcConfig[i].tag)
continue;
adcDevice_t * adc = &adcHardware[adcConfig[i].adcDevice];
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_CH1 + (i - ADC_CHN_1), 0);
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_MODE_ANALOG, 0, GPIO_NOPULL));
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
adcConfig[i].dmaIndex = adc->usedChannelCount++;
adcConfig[i].sampleTime = ADC_SAMPLETIME_387CYCLES_5;
adcConfig[i].enabled = true;
adc->enabled = true;
configuredAdcChannels++;
}
if (configuredAdcChannels == 0)
return;
for (int i = 0; i < ADCDEV_COUNT; i++) {
if (adcHardware[i].enabled) {
adcInstanceInit(i);
}
}
}

View file

@ -0,0 +1,128 @@
/*
* 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 <string.h>
#include <platform.h>
#include "common/utils.h"
#include "drivers/nvic.h"
#include "drivers/dma.h"
#include "drivers/rcc.h"
/*
* DMA descriptors.
*/
static dmaChannelDescriptor_t dmaDescriptors[] = {
[0] = DEFINE_DMA_CHANNEL(1, 0, 0), // DMA1_ST0
[1] = DEFINE_DMA_CHANNEL(1, 1, 6), // DMA1_ST1
[2] = DEFINE_DMA_CHANNEL(1, 2, 16), // DMA1_ST2
[3] = DEFINE_DMA_CHANNEL(1, 3, 22), // DMA1_ST3
[4] = DEFINE_DMA_CHANNEL(1, 4, 32), // DMA1_ST4
[5] = DEFINE_DMA_CHANNEL(1, 5, 38), // DMA1_ST5
[6] = DEFINE_DMA_CHANNEL(1, 6, 48), // DMA1_ST6
[7] = DEFINE_DMA_CHANNEL(1, 7, 54), // DMA1_ST7
[8] = DEFINE_DMA_CHANNEL(2, 0, 0), // DMA2_ST0
[9] = DEFINE_DMA_CHANNEL(2, 1, 6), // DMA2_ST1
[10] = DEFINE_DMA_CHANNEL(2, 2, 16), // DMA2_ST2
[11] = DEFINE_DMA_CHANNEL(2, 3, 22), // DMA2_ST3
[12] = DEFINE_DMA_CHANNEL(2, 4, 32), // DMA2_ST4
[13] = DEFINE_DMA_CHANNEL(2, 5, 38), // DMA2_ST5
[14] = DEFINE_DMA_CHANNEL(2, 6, 48), // DMA2_ST6
[15] = DEFINE_DMA_CHANNEL(2, 7, 54), // DMA2_ST7
};
/*
* DMA IRQ Handlers
*/
DEFINE_DMA_IRQ_HANDLER(1, 0, 0) // DMA1_ST0
DEFINE_DMA_IRQ_HANDLER(1, 1, 1) // DMA1_ST1
DEFINE_DMA_IRQ_HANDLER(1, 2, 2) // DMA1_ST2
DEFINE_DMA_IRQ_HANDLER(1, 3, 3) // DMA1_ST3
DEFINE_DMA_IRQ_HANDLER(1, 4, 4) // DMA1_ST4
DEFINE_DMA_IRQ_HANDLER(1, 5, 5) // DMA1_ST5
DEFINE_DMA_IRQ_HANDLER(1, 6, 6) // DMA1_ST6
DEFINE_DMA_IRQ_HANDLER(1, 7, 7) // DMA1_ST7
DEFINE_DMA_IRQ_HANDLER(2, 0, 8) // DMA2_ST0
DEFINE_DMA_IRQ_HANDLER(2, 1, 9) // DMA2_ST1
DEFINE_DMA_IRQ_HANDLER(2, 2, 10) // DMA2_ST2
DEFINE_DMA_IRQ_HANDLER(2, 3, 11) // DMA2_ST3
DEFINE_DMA_IRQ_HANDLER(2, 4, 12) // DMA2_ST4
DEFINE_DMA_IRQ_HANDLER(2, 5, 13) // DMA2_ST5
DEFINE_DMA_IRQ_HANDLER(2, 6, 14) // DMA2_ST6
DEFINE_DMA_IRQ_HANDLER(2, 7, 15) // DMA2_ST7
DMA_t dmaGetByTag(dmaTag_t tag)
{
for (unsigned i = 0; i < ARRAYLEN(dmaDescriptors); i++) {
if (DMATAG_GET_DMA(dmaDescriptors[i].tag) == DMATAG_GET_DMA(tag) && DMATAG_GET_STREAM(dmaDescriptors[i].tag) == DMATAG_GET_STREAM(tag)) {
return (DMA_t)&dmaDescriptors[i];
}
}
return (DMA_t) NULL;
}
void dmaEnableClock(DMA_t dma)
{
if (dma->dma == DMA1) {
RCC_ClockCmd(RCC_AHB1(DMA1), ENABLE);
}
else {
RCC_ClockCmd(RCC_AHB1(DMA2), ENABLE);
}
}
resourceOwner_e dmaGetOwner(DMA_t dma)
{
return dma->owner;
}
void dmaInit(DMA_t dma, resourceOwner_e owner, uint8_t resourceIndex)
{
dmaEnableClock(dma);
dma->owner = owner;
dma->resourceIndex = resourceIndex;
}
void dmaSetHandler(DMA_t dma, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
{
dmaEnableClock(dma);
dma->irqHandlerCallback = callback;
dma->userParam = userParam;
HAL_NVIC_SetPriority(dma->irqNumber, priority, 0);
HAL_NVIC_EnableIRQ(dma->irqNumber);
}
DMA_t dmaGetByRef(const DMA_Stream_TypeDef* ref)
{
for (unsigned i = 0; i < (sizeof(dmaDescriptors) / sizeof(dmaDescriptors[0])); i++) {
if (ref == dmaDescriptors[i].ref) {
return &dmaDescriptors[i];
}
}
return NULL;
}

View file

@ -24,7 +24,7 @@ extiChannelRec_t extiChannelRecs[16];
static const uint8_t extiGroups[16] = { 0, 1, 2, 3, 4, 5, 5, 5, 5, 5, 6, 6, 6, 6, 6, 6 };
static uint8_t extiGroupPriority[EXTI_IRQ_GROUPS];
#if defined(STM32F4) || defined(STM32F7)
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
EXTI0_IRQn,
EXTI1_IRQn,
@ -48,6 +48,15 @@ static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
# warning "Unknown CPU"
#endif
// Absorb the difference in IMR and PR assignments to registers
#if defined(STM32H7)
#define EXTI_REG_IMR (EXTI_D1->IMR1)
#define EXTI_REG_PR (EXTI_D1->PR1)
#else
#define EXTI_REG_IMR (EXTI->IMR)
#define EXTI_REG_PR (EXTI->PR)
#endif
void EXTIInit(void)
{
@ -64,7 +73,7 @@ void EXTIHandlerInit(extiCallbackRec_t *self, extiHandlerCallback *fn)
self->fn = fn;
}
#if defined(STM32F7)
#if defined(STM32F7) || defined(STM32H7)
void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t config)
{
(void)config;
@ -156,23 +165,23 @@ void EXTIRelease(IO_t io)
void EXTIEnable(IO_t io, bool enable)
{
#if defined(STM32F4) || defined(STM32F7)
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
uint32_t extiLine = IO_EXTI_Line(io);
if (!extiLine)
return;
if (enable)
EXTI->IMR |= extiLine;
EXTI_REG_IMR |= extiLine;
else
EXTI->IMR &= ~extiLine;
EXTI_REG_IMR &= ~extiLine;
#elif defined(STM32F303xC)
int extiLine = IO_EXTI_Line(io);
if (extiLine < 0)
return;
// assume extiLine < 32 (valid for all EXTI pins)
if (enable)
EXTI->IMR |= 1 << extiLine;
EXTI_REG_IMR |= 1 << extiLine;
else
EXTI->IMR &= ~(1 << extiLine);
EXTI_REG_IMR &= ~(1 << extiLine);
#else
# error "Unsupported target"
#endif
@ -180,13 +189,13 @@ void EXTIEnable(IO_t io, bool enable)
void EXTI_IRQHandler(void)
{
uint32_t exti_active = EXTI->IMR & EXTI->PR;
uint32_t exti_active = EXTI_REG_IMR & EXTI_REG_PR;
while (exti_active) {
unsigned idx = 31 - __builtin_clz(exti_active);
uint32_t mask = 1 << idx;
extiChannelRecs[idx].handler->fn(extiChannelRecs[idx].handler);
EXTI->PR = mask; // clear pending mask (by writing 1)
EXTI_REG_PR = mask; // clear pending mask (by writing 1)
exti_active &= ~mask;
}
}
@ -201,7 +210,7 @@ void EXTI_IRQHandler(void)
_EXTI_IRQ_HANDLER(EXTI0_IRQHandler);
_EXTI_IRQ_HANDLER(EXTI1_IRQHandler);
#if defined(STM32F7)
#if defined(STM32F7) || defined(STM32H7)
_EXTI_IRQ_HANDLER(EXTI2_IRQHandler);
#elif defined(STM32F3) || defined(STM32F4)
_EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler);

View file

@ -109,7 +109,7 @@
#define SYM_AH_CH_CENTER 0x7E // 126 Crossair center
// 0x7F // 127 -
#define SYM_GLIDESLOPE 0x7F // 127 Glideslope
#define SYM_AH_H_START 0x80 // 128 to 136 Horizontal AHI

View file

@ -331,6 +331,10 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode,
s->Handle.Instance = uart->dev;
if (uart->rcc) {
RCC_ClockCmd(uart->rcc, ENABLE);
}
IO_t tx = IOGetByTag(uart->tx);
IO_t rx = IOGetByTag(uart->rx);

View file

@ -45,6 +45,7 @@ FILE_COMPILE_FOR_SPEED
#include "sensors/boardalignment.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/compass.h"
#include "sensors/pitotmeter.h"
#include "sensors/gyro.h"
#include "sensors/battery.h"
@ -135,7 +136,7 @@ static emergencyArmingState_t emergencyArming;
static bool prearmWasReset = false; // Prearm must be reset (RC Mode not active) before arming is possible
static timeMs_t prearmActivationTime = 0;
bool isCalibrating(void)
bool areSensorsCalibrating(void)
{
#ifdef USE_BARO
if (sensors(SENSOR_BARO) && !baroIsCalibrationComplete()) {
@ -143,6 +144,12 @@ bool isCalibrating(void)
}
#endif
#ifdef USE_MAG
if (sensors(SENSOR_MAG) && !compassIsCalibrationComplete()) {
return true;
}
#endif
#ifdef USE_PITOT
if (sensors(SENSOR_PITOT) && !pitotIsCalibrationComplete()) {
return true;
@ -183,7 +190,7 @@ static void updateArmingStatus(void)
} else {
/* CHECK: Run-time calibration */
static bool calibratingFinishedBeep = false;
if (isCalibrating()) {
if (areSensorsCalibrating()) {
ENABLE_ARMING_FLAG(ARMING_DISABLED_SENSORS_CALIBRATING);
calibratingFinishedBeep = false;
}
@ -216,7 +223,7 @@ static void updateArmingStatus(void)
/* CHECK: pitch / roll sticks centered when NAV_LAUNCH_MODE enabled */
if (isNavLaunchEnabled()) {
if (areSticksDeflectedMoreThanPosHoldDeadband()) {
if (areSticksDeflected()) {
ENABLE_ARMING_FLAG(ARMING_DISABLED_ROLLPITCH_NOT_CENTERED);
} else {
DISABLE_ARMING_FLAG(ARMING_DISABLED_ROLLPITCH_NOT_CENTERED);
@ -711,7 +718,7 @@ void processRx(timeUs_t currentTimeUs)
// Handle passthrough mode
if (STATE(FIXED_WING_LEGACY)) {
if ((IS_RC_MODE_ACTIVE(BOXMANUAL) && !navigationRequiresAngleMode() && !failsafeRequiresAngleMode()) || // Normal activation of passthrough
(!ARMING_FLAG(ARMED) && isCalibrating())){ // Backup - if we are not armed - enforce passthrough while calibrating
(!ARMING_FLAG(ARMED) && areSensorsCalibrating())){ // Backup - if we are not armed - enforce passthrough while calibrating
ENABLE_FLIGHT_MODE(MANUAL_MODE);
} else {
DISABLE_FLIGHT_MODE(MANUAL_MODE);

View file

@ -43,7 +43,7 @@ disarmReason_t getDisarmReason(void);
void emergencyArmingUpdate(bool armingSwitchIsOn);
bool isCalibrating(void);
bool areSensorsCalibrating(void);
float getFlightTime(void);
float getArmTime(void);

View file

@ -326,7 +326,7 @@ void initActiveBoxIds(void)
#endif
}
#define IS_ENABLED(mask) (mask == 0 ? 0 : 1)
#define IS_ENABLED(mask) ((mask) == 0 ? 0 : 1)
#define CHECK_ACTIVE_BOX(condition, index) do { if (IS_ENABLED(condition)) { activeBoxes[index] = 1; } } while(0)
void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags)

View file

@ -71,12 +71,13 @@ stickPositions_e rcStickPositions;
FASTRAM int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW
PG_REGISTER_WITH_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 2);
PG_REGISTER_WITH_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 3);
PG_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig,
.deadband = SETTING_DEADBAND_DEFAULT,
.yaw_deadband = SETTING_YAW_DEADBAND_DEFAULT,
.pos_hold_deadband = SETTING_POS_HOLD_DEADBAND_DEFAULT,
.control_deadband = SETTING_CONTROL_DEADBAND_DEFAULT,
.alt_hold_deadband = SETTING_ALT_HOLD_DEADBAND_DEFAULT,
.mid_throttle_deadband = SETTING_3D_DEADBAND_THROTTLE_DEFAULT,
.airmodeHandlingType = SETTING_AIRMODE_TYPE_DEFAULT,
@ -97,9 +98,14 @@ bool areSticksInApModePosition(uint16_t ap_mode)
return ABS(rcCommand[ROLL]) < ap_mode && ABS(rcCommand[PITCH]) < ap_mode;
}
bool areSticksDeflectedMoreThanPosHoldDeadband(void)
bool areSticksDeflected(void)
{
return (ABS(rcCommand[ROLL]) > rcControlsConfig()->pos_hold_deadband) || (ABS(rcCommand[PITCH]) > rcControlsConfig()->pos_hold_deadband);
return (ABS(rcCommand[ROLL]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[PITCH]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[YAW]) > rcControlsConfig()->control_deadband);
}
bool isRollPitchStickDeflected(void)
{
return (ABS(rcCommand[ROLL]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[PITCH]) > rcControlsConfig()->control_deadband);
}
throttleStatus_e FAST_CODE NOINLINE calculateThrottleStatus(throttleStatusType_e type)

View file

@ -84,7 +84,8 @@ extern int16_t rcCommand[4];
typedef struct rcControlsConfig_s {
uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero.
uint8_t yaw_deadband; // introduce a deadband around the stick center for yaw axis. Must be greater than zero.
uint8_t pos_hold_deadband; // Adds ability to adjust the Hold-position when moving the sticks (assisted mode)
uint8_t pos_hold_deadband; // Deadband for position hold
uint8_t control_deadband; // General deadband to check if sticks are deflected, us PWM.
uint8_t alt_hold_deadband; // Defines the neutral zone of throttle stick during altitude hold
uint16_t mid_throttle_deadband; // default throttle deadband from MIDRC
uint8_t airmodeHandlingType; // Defaults to ANTI_WINDUP triggered at sticks centered
@ -106,7 +107,8 @@ stickPositions_e getRcStickPositions(void);
bool checkStickPosition(stickPositions_e stickPos);
bool areSticksInApModePosition(uint16_t ap_mode);
bool areSticksDeflectedMoreThanPosHoldDeadband(void);
bool areSticksDeflected(void);
bool isRollPitchStickDeflected(void);
throttleStatus_e calculateThrottleStatus(throttleStatusType_e type);
rollPitchStatus_e calculateRollPitchCenterStatus(void);
void processRcStickPositions(throttleStatus_e throttleStatus);

View file

@ -182,12 +182,12 @@ tables:
constants:
RPYL_PID_MIN: 0
RPYL_PID_MAX: 200
RPYL_PID_MAX: 255
MANUAL_RATE_MIN: 0
MANUAL_RATE_MAX: 100
ROLL_PITCH_RATE_MIN: 6
ROLL_PITCH_RATE_MIN: 4
ROLL_PITCH_RATE_MAX: 180
groups:
@ -214,7 +214,7 @@ groups:
description: "Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz"
default_value: 250
field: gyro_anti_aliasing_lpf_hz
max: 255
max: 1000
- name: gyro_anti_aliasing_lpf_type
description: "Specifies the type of the software LPF of the gyro signals."
default_value: "PT1"
@ -1289,7 +1289,7 @@ groups:
description: "Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure."
default_value: 20
field: stabilized.rates[FD_YAW]
min: 2
min: 1
max: 180
- name: manual_rc_expo
description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]"
@ -1505,7 +1505,12 @@ groups:
min: 0
max: 100
- name: pos_hold_deadband
description: "Stick deadband in [r/c points], applied after r/c deadband and expo"
description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used for adjustments in navigation modes."
default_value: 10
min: 2
max: 250
- name: control_deadband
description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used to check if sticks are centered."
default_value: 10
min: 2
max: 250
@ -2118,12 +2123,6 @@ groups:
field: fixedWingLevelTrimGain
min: 0
max: 20
- name: fw_level_pitch_deadband
description: "Deadband for automatic leveling when AUTOLEVEL mode is used."
default_value: 5
field: fixedWingLevelTrimDeadband
min: 0
max: 20
- name: PG_PID_AUTOTUNE_CONFIG
type: pidAutotuneConfig_t
@ -2161,7 +2160,7 @@ groups:
type: uint8_t
- name: fw_autotune_max_rate_deflection
description: "The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`."
default_value: 80
default_value: 90
field: fw_max_rate_deflection
min: 50
max: 100
@ -2687,6 +2686,12 @@ groups:
field: fw.launch_idle_throttle
min: 1000
max: 2000
- name: nav_fw_launch_idle_motor_delay
description: "Delay between raising throttle and motor starting at idle throttle (ms)"
default_value: 0
field: fw.launch_idle_motor_timer
min: 0
max: 60000
- name: nav_fw_launch_motor_delay
description: "Delay between detected launch and launch sequence start and throttling up (ms)"
default_value: 500
@ -3126,6 +3131,13 @@ groups:
field: link_quality_alarm
min: 0
max: 100
- name: osd_rssi_dbm_alarm
condition: USE_SERIALRX_CRSF
description: "RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm"
default_value: 0
field: rssi_dbm_alarm
min: -130
max: 0
- name: osd_temp_label_align
description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`"
default_value: "LEFT"
@ -3164,11 +3176,16 @@ groups:
min: -2
max: 2
- name: osd_camera_uptilt
description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal"
description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal. Used for correct display of HUD items and AHI (when enabled)."
default_value: 0
field: camera_uptilt
min: -40
max: 80
- name: osd_ahi_camera_uptilt_comp
description: "When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees. When set to `OFF`, the AHI will appear in the center of the OSD regardless of camera angle, but can still be shifted up and down using `osd_horizon_offset` (`osd_ahi_vertical_offset` for pixel-OSD)."
default_value: OFF
field: ahi_camera_uptilt_comp
type: bool
- name: osd_camera_fov_h
description: "Horizontal field of view for the camera in degres"
default_value: 135

View file

@ -504,7 +504,7 @@ static float imuCalculateAccelerometerWeight(const float dT)
float accWeight_RateIgnore = 1.0f;
if (ARMING_FLAG(ARMED) && STATE(FIXED_WING_LEGACY) && imuConfig()->acc_ignore_rate) {
const float rotRateMagnitude = fast_fsqrtf(vectorNormSquared(&imuMeasuredRotationBF));
const float rotRateMagnitude = fast_fsqrtf(sq(imuMeasuredRotationBF.y) + sq(imuMeasuredRotationBF.z));
const float rotRateMagnitudeFiltered = pt1FilterApply4(&rotRateFilter, rotRateMagnitude, IMU_CENTRIFUGAL_LPF, dT);
if (imuConfig()->acc_ignore_slope) {

View file

@ -308,7 +308,6 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
.fixedWingLevelTrim = SETTING_FW_LEVEL_PITCH_TRIM_DEFAULT,
.fixedWingLevelTrimGain = SETTING_FW_LEVEL_PITCH_GAIN_DEFAULT,
.fixedWingLevelTrimDeadband = SETTING_FW_LEVEL_PITCH_DEADBAND_DEFAULT,
#ifdef USE_SMITH_PREDICTOR
.smithPredictorStrength = SETTING_SMITH_PREDICTOR_STRENGTH_DEFAULT,
@ -616,21 +615,6 @@ static void pidLevel(pidState_t *pidState, flight_dynamics_index_t axis, float h
DEBUG_SET(DEBUG_AUTOLEVEL, 1, fixedWingLevelTrim * 10);
DEBUG_SET(DEBUG_AUTOLEVEL, 2, getEstimatedActualVelocity(Z));
/*
* fixedWingLevelTrim has opposite sign to rcCommand.
* Positive rcCommand means nose should point downwards
* Negative rcCommand mean nose should point upwards
* This is counter intuitive and a natural way suggests that + should mean UP
* This is why fixedWingLevelTrim has opposite sign to rcCommand
* Positive fixedWingLevelTrim means nose should point upwards
* Negative fixedWingLevelTrim means nose should point downwards
*/
angleTarget -= fixedWingLevelTrim;
DEBUG_SET(DEBUG_AUTOLEVEL, 3, angleTarget * 10);
}
//PITCH trim applied by a AutoLevel flight mode and manual pitch trimming
if (axis == FD_PITCH && STATE(AIRPLANE)) {
/*
* fixedWingLevelTrim has opposite sign to rcCommand.
* Positive rcCommand means nose should point downwards
@ -641,6 +625,7 @@ static void pidLevel(pidState_t *pidState, flight_dynamics_index_t axis, float h
* Negative fixedWingLevelTrim means nose should point downwards
*/
angleTarget -= DEGREES_TO_DECIDEGREES(fixedWingLevelTrim);
DEBUG_SET(DEBUG_AUTOLEVEL, 3, angleTarget * 10);
}
#ifdef USE_SECONDARY_IMU
@ -795,7 +780,7 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh
pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidProfile()->fixedWingItermThrowLimit, pidProfile()->fixedWingItermThrowLimit);
}
axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf, -pidState->pidSumLimit, +pidState->pidSumLimit);
axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -pidState->pidSumLimit, +pidState->pidSumLimit);
#ifdef USE_AUTOTUNE_FIXED_WING
if (FLIGHT_MODE(AUTO_TUNE) && !FLIGHT_MODE(MANUAL_MODE)) {
@ -1327,11 +1312,10 @@ void updateFixedWingLevelTrim(timeUs_t currentTimeUs)
*/
pidControllerFlags_e flags = PID_LIMIT_INTEGRATOR;
//Iterm should freeze when pitch stick is deflected
//Iterm should freeze when sticks are deflected
if (
!IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) ||
rxGetChannelValue(PITCH) > (PWM_RANGE_MIDDLE + pidProfile()->fixedWingLevelTrimDeadband) ||
rxGetChannelValue(PITCH) < (PWM_RANGE_MIDDLE - pidProfile()->fixedWingLevelTrimDeadband) ||
areSticksDeflected() ||
(!FLIGHT_MODE(ANGLE_MODE) && !FLIGHT_MODE(HORIZON_MODE)) ||
navigationIsControllingAltitude()
) {
@ -1355,3 +1339,8 @@ void updateFixedWingLevelTrim(timeUs_t currentTimeUs)
previousArmingState = !!ARMING_FLAG(ARMED);
}
float getFixedWingLevelTrim(void)
{
return STATE(AIRPLANE) ? fixedWingLevelTrim : 0;
}

View file

@ -165,7 +165,6 @@ typedef struct pidProfile_s {
float fixedWingLevelTrim;
float fixedWingLevelTrimGain;
float fixedWingLevelTrimDeadband;
#ifdef USE_SMITH_PREDICTOR
float smithPredictorStrength;
float smithPredictorDelay;
@ -233,3 +232,4 @@ void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRa
pidType_e pidIndexGetType(pidIndex_e pidIndex);
void updateFixedWingLevelTrim(timeUs_t currentTimeUs);
float getFixedWingLevelTrim(void);

View file

@ -47,14 +47,14 @@
#include "flight/pid.h"
#define AUTOTUNE_FIXED_WING_MIN_FF 10
#define AUTOTUNE_FIXED_WING_MAX_FF 200
#define AUTOTUNE_FIXED_WING_MAX_FF 255
#define AUTOTUNE_FIXED_WING_MIN_ROLL_PITCH_RATE 40
#define AUTOTUNE_FIXED_WING_MIN_YAW_RATE 10
#define AUTOTUNE_FIXED_WING_MAX_RATE 720
#define AUTOTUNE_FIXED_WING_CONVERGENCE_RATE 10
#define AUTOTUNE_FIXED_WING_SAMPLE_INTERVAL 20 // ms
#define AUTOTUNE_FIXED_WING_SAMPLES 1000 // Use averagea over the last 20 seconds
#define AUTOTUNE_FIXED_WING_MIN_SAMPLES 250 // Start updating tune after 5 seconds
#define AUTOTUNE_FIXED_WING_SAMPLES 1000 // Use average over the last 20 seconds of hard maneuvers
#define AUTOTUNE_FIXED_WING_MIN_SAMPLES 250 // Start updating tune after 5 seconds of hard maneuvers
PG_REGISTER_WITH_RESET_TEMPLATE(pidAutotuneConfig_t, pidAutotuneConfig, PG_PID_AUTOTUNE_CONFIG, 2);

View file

@ -192,7 +192,6 @@ void powerLimiterApply(int16_t *throttleCommand) {
currentThrottleCommand = currentThrAttned;
} else {
wasLimitingCurrent = false;
currentThrAttnIntegrator = 0;
pt1FilterReset(&currentThrAttnFilter, 0);
currentThrottleCommand = *throttleCommand;
@ -222,7 +221,6 @@ void powerLimiterApply(int16_t *throttleCommand) {
powerThrottleCommand = powerThrAttned;
} else {
wasLimitingPower = false;
powerThrAttnIntegrator = 0;
pt1FilterReset(&powerThrAttnFilter, 0);
powerThrottleCommand = *throttleCommand;

View file

@ -490,6 +490,7 @@ void processServoAutotrimMode(void)
#define SERVO_AUTOTRIM_CENTER_MIN 1300
#define SERVO_AUTOTRIM_CENTER_MAX 1700
#define SERVO_AUTOTRIM_UPDATE_SIZE 5
#define SERVO_AUTOTRIM_ATIITUDE_LIMIT 50 // 5 degrees
void processContinuousServoAutotrim(const float dT)
{
@ -497,21 +498,22 @@ void processContinuousServoAutotrim(const float dT)
static servoAutotrimState_e trimState = AUTOTRIM_IDLE;
static uint32_t servoMiddleUpdateCount;
const float rotRateMagnitude = fast_fsqrtf(vectorNormSquared(&imuMeasuredRotationBF));
const float rotRateMagnitudeFiltered = pt1FilterApply4(&rotRateFilter, rotRateMagnitude, SERVO_AUTOTRIM_FILTER_CUTOFF, dT);
const float targetRateMagnitude = getTotalRateTarget();
const float targetRateMagnitudeFiltered = pt1FilterApply4(&targetRateFilter, targetRateMagnitude, SERVO_AUTOTRIM_FILTER_CUTOFF, dT);
const float rotRateMagnitudeFiltered = pt1FilterApply4(&rotRateFilter, fast_fsqrtf(vectorNormSquared(&imuMeasuredRotationBF)), SERVO_AUTOTRIM_FILTER_CUTOFF, dT);
const float targetRateMagnitudeFiltered = pt1FilterApply4(&targetRateFilter, getTotalRateTarget(), SERVO_AUTOTRIM_FILTER_CUTOFF, dT);
if (ARMING_FLAG(ARMED)) {
trimState = AUTOTRIM_COLLECTING;
if ((millis() - lastUpdateTimeMs) > 500) {
const bool planeIsFlyingStraight = rotRateMagnitudeFiltered <= DEGREES_TO_RADIANS(servoConfig()->servo_autotrim_rotation_limit);
const bool noRotationCommanded = targetRateMagnitudeFiltered <= servoConfig()->servo_autotrim_rotation_limit;
const bool planeIsFlyingLevel = calculateCosTiltAngle() >= 0.878153032f;
const bool sticksAreCentered = !areSticksDeflected();
const bool planeIsFlyingLevel = ABS(attitude.values.pitch + DEGREES_TO_DECIDEGREES(getFixedWingLevelTrim())) <= SERVO_AUTOTRIM_ATIITUDE_LIMIT
&& ABS(attitude.values.roll) <= SERVO_AUTOTRIM_ATIITUDE_LIMIT;
if (
planeIsFlyingStraight &&
noRotationCommanded &&
planeIsFlyingLevel &&
sticksAreCentered &&
!FLIGHT_MODE(MANUAL_MODE) &&
isGPSHeadingValid() // TODO: proper flying detection
) {

View file

@ -132,6 +132,10 @@ static const uint8_t beep_launchModeBeep[] = {
static const uint8_t beep_launchModeLowThrottleBeep[] = {
5, 5, 5, 5, 3, 100, BEEPER_COMMAND_STOP
};
// 4 short beeps and a pause. Warning motor about to start at idle throttle
static const uint8_t beep_launchModeIdleStartBeep[] = {
5, 5, 5, 5, 5, 5, 5, 80, BEEPER_COMMAND_STOP
};
// short beeps
static const uint8_t beep_hardwareFailure[] = {
10, 10, BEEPER_COMMAND_STOP
@ -196,11 +200,12 @@ typedef struct beeperTableEntry_s {
{ BEEPER_ENTRY(BEEPER_USB, 18, NULL, "ON_USB") },
{ BEEPER_ENTRY(BEEPER_LAUNCH_MODE_ENABLED, 19, beep_launchModeBeep, "LAUNCH_MODE") },
{ BEEPER_ENTRY(BEEPER_LAUNCH_MODE_LOW_THROTTLE, 20, beep_launchModeLowThrottleBeep, "LAUNCH_MODE_LOW_THROTTLE") },
{ BEEPER_ENTRY(BEEPER_CAM_CONNECTION_OPEN, 21, beep_camOpenBeep, "CAM_CONNECTION_OPEN") },
{ BEEPER_ENTRY(BEEPER_CAM_CONNECTION_CLOSE, 22, beep_camCloseBeep, "CAM_CONNECTION_CLOSED") },
{ BEEPER_ENTRY(BEEPER_LAUNCH_MODE_IDLE_START, 21, beep_launchModeIdleStartBeep, "LAUNCH_MODE_IDLE_START") },
{ BEEPER_ENTRY(BEEPER_CAM_CONNECTION_OPEN, 22, beep_camOpenBeep, "CAM_CONNECTION_OPEN") },
{ BEEPER_ENTRY(BEEPER_CAM_CONNECTION_CLOSE, 23, beep_camCloseBeep, "CAM_CONNECTION_CLOSED") },
{ BEEPER_ENTRY(BEEPER_ALL, 23, NULL, "ALL") },
{ BEEPER_ENTRY(BEEPER_PREFERENCE, 24, NULL, "PREFERED") },
{ BEEPER_ENTRY(BEEPER_ALL, 24, NULL, "ALL") },
{ BEEPER_ENTRY(BEEPER_PREFERENCE, 25, NULL, "PREFERED") },
};
static const beeperTableEntry_t *currentBeeperEntry = NULL;
@ -339,8 +344,7 @@ void beeperUpdate(timeUs_t currentTimeUs)
if (!beeperIsOn) {
#ifdef USE_DSHOT
if (!areMotorsRunning()
&& beeperConfig()->dshot_beeper_enabled
if (isMotorProtocolDshot() && !areMotorsRunning() && beeperConfig()->dshot_beeper_enabled
&& currentTimeUs - lastDshotBeeperCommandTimeUs > getDShotBeaconGuardDelayUs())
{
lastDshotBeeperCommandTimeUs = currentTimeUs;

View file

@ -44,6 +44,7 @@ typedef enum {
BEEPER_USB, // Some boards have beeper powered USB connected
BEEPER_LAUNCH_MODE_ENABLED, // Fixed-wing launch mode enabled
BEEPER_LAUNCH_MODE_LOW_THROTTLE, // Fixed-wing launch mode enabled, but throttle is low
BEEPER_LAUNCH_MODE_IDLE_START, // Fixed-wing launch mode enabled, motor about to start at idle after set delay
BEEPER_CAM_CONNECTION_OPEN, // When the 5 key simulation stated
BEEPER_CAM_CONNECTION_CLOSE, // When the 5 key simulation stop

View file

@ -194,7 +194,7 @@ static bool osdDisplayHasCanvas;
#define AH_MAX_PITCH_DEFAULT 20 // Specify default maximum AHI pitch value displayed (degrees)
PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 2);
PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 4);
PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 0);
static int digitCount(int32_t value)
@ -449,29 +449,30 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid)
*/
void osdFormatAltitudeSymbol(char *buff, int32_t alt)
{
int digits = alt < 0 ? 4 : 3;
switch ((osd_unit_e)osdConfig()->units) {
case OSD_UNIT_UK:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
if (osdFormatCentiNumber(buff , CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, 3)) {
if (osdFormatCentiNumber(buff , CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, digits)) {
// Scaled to kft
buff[3] = SYM_ALT_KFT;
buff[digits] = SYM_ALT_KFT;
} else {
// Formatted in feet
buff[3] = SYM_ALT_FT;
buff[digits] = SYM_ALT_FT;
}
buff[4] = '\0';
buff[digits + 1] = '\0';
break;
case OSD_UNIT_METRIC:
// alt is alredy in cm
if (osdFormatCentiNumber(buff, alt, 1000, 0, 2, 3)) {
if (osdFormatCentiNumber(buff, alt, 1000, 0, 2, digits)) {
// Scaled to km
buff[3] = SYM_ALT_KM;
buff[digits] = SYM_ALT_KM;
} else {
// Formatted in m
buff[3] = SYM_ALT_M;
buff[digits] = SYM_ALT_M;
}
buff[4] = '\0';
buff[digits + 1] = '\0';
break;
}
}
@ -1383,6 +1384,25 @@ static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY,
displayWriteWithAttr(osdDisplayPort, elemPosX + strlen(str) + 1 + valueOffset, elemPosY, buff, elemAttr);
}
int8_t getGeoWaypointNumber(int8_t waypointIndex)
{
static int8_t lastWaypointIndex = 1;
static int8_t geoWaypointIndex;
if (waypointIndex != lastWaypointIndex) {
lastWaypointIndex = geoWaypointIndex = waypointIndex;
for (uint8_t i = 0; i <= waypointIndex; i++) {
if (posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI ||
posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD ||
posControl.waypointList[i].action == NAV_WP_ACTION_JUMP) {
geoWaypointIndex -= 1;
}
}
}
return geoWaypointIndex + 1;
}
static bool osdDrawSingleElement(uint8_t item)
{
uint16_t pos = osdLayoutsConfig()->item_pos[currentLayout][item];
@ -1495,6 +1515,27 @@ static bool osdDrawSingleElement(uint8_t item)
break;
}
case OSD_GLIDESLOPE:
{
float horizontalSpeed = gpsSol.groundSpeed;
float sinkRate = -getEstimatedActualVelocity(Z);
static pt1Filter_t gsFilterState;
const timeMs_t currentTimeMs = millis();
static timeMs_t gsUpdatedTimeMs;
float glideSlope = horizontalSpeed / sinkRate;
glideSlope = pt1FilterApply4(&gsFilterState, isnormal(glideSlope) ? glideSlope : 200, 0.5, MS2S(currentTimeMs - gsUpdatedTimeMs));
gsUpdatedTimeMs = currentTimeMs;
buff[0] = SYM_GLIDESLOPE;
if (glideSlope > 0.0f && glideSlope < 100.0f) {
osdFormatCentiNumber(buff + 1, glideSlope * 100.0f, 0, 2, 0, 3);
} else {
buff[1] = buff[2] = buff[3] = '-';
}
buff[4] = '\0';
break;
}
case OSD_GPS_LAT:
osdFormatCoordinate(buff, SYM_LAT, gpsSol.llh.lat);
break;
@ -1858,6 +1899,8 @@ static bool osdDrawSingleElement(uint8_t item)
}
if (!failsafeIsReceivingRxData()){
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
} else if (osdConfig()->rssi_dbm_alarm && rssi < osdConfig()->rssi_dbm_alarm) {
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
}
break;
}
@ -1984,8 +2027,9 @@ static bool osdDrawSingleElement(uint8_t item)
fpVector3_t poi;
geoConvertGeodeticToLocal(&poi, &posControl.gpsOrigin, &wp2, waypointMissionAltConvMode(posControl.waypointList[j].p3));
int32_t altConvModeAltitude = waypointMissionAltConvMode(posControl.waypointList[j].p3) == GEO_ALT_ABSOLUTE ? osdGetAltitudeMsl() : osdGetAltitude();
while (j > 9) j -= 10; // Only the last digit displayed if WP>=10, no room for more
osdHudDrawPoi(calculateDistanceToDestination(&poi) / 100, osdGetHeadingAngle(calculateBearingToDestination(&poi) / 100), (posControl.waypointList[j].alt - altConvModeAltitude)/ 100, 2, SYM_WAYPOINT, 49 + j, i);
j = getGeoWaypointNumber(j);
while (j > 9) j -= 10; // Only the last digit displayed if WP>=10, no room for more (48 = ascii 0)
osdHudDrawPoi(calculateDistanceToDestination(&poi) / 100, osdGetHeadingAngle(calculateBearingToDestination(&poi) / 100), (posControl.waypointList[j].alt - altConvModeAltitude)/ 100, 2, SYM_WAYPOINT, 48 + j, i);
}
}
}
@ -2028,7 +2072,8 @@ static bool osdDrawSingleElement(uint8_t item)
rollAngle = DECIDEGREES_TO_RADIANS(attitude.values.roll);
pitchAngle = DECIDEGREES_TO_RADIANS(attitude.values.pitch);
#endif
pitchAngle -= DEGREES_TO_RADIANS(osdConfig()->camera_uptilt);
pitchAngle -= osdConfig()->ahi_camera_uptilt_comp ? DEGREES_TO_RADIANS(osdConfig()->camera_uptilt) : 0;
pitchAngle += DEGREES_TO_RADIANS(getFixedWingLevelTrim());
if (osdConfig()->ahi_reverse_roll) {
rollAngle = -rollAngle;
}
@ -2283,7 +2328,7 @@ static bool osdDrawSingleElement(uint8_t item)
dateTime_t dateTime;
rtcGetDateTimeLocal(&dateTime);
buff[0] = SYM_CLOCK;
tfp_sprintf(buff + 1, "%02u:%02u", dateTime.hours, dateTime.minutes);
tfp_sprintf(buff + 1, "%02u:%02u:%02u", dateTime.hours, dateTime.minutes, dateTime.seconds);
break;
}
@ -2881,6 +2926,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
.snr_alarm = SETTING_OSD_SNR_ALARM_DEFAULT,
.crsf_lq_format = SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT,
.link_quality_alarm = SETTING_OSD_LINK_QUALITY_ALARM_DEFAULT,
.rssi_dbm_alarm = SETTING_OSD_RSSI_DBM_ALARM_DEFAULT,
#endif
#ifdef USE_TEMPERATURE_SENSOR
.temp_label_align = SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT,
@ -2894,6 +2940,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
.crosshairs_style = SETTING_OSD_CROSSHAIRS_STYLE_DEFAULT,
.horizon_offset = SETTING_OSD_HORIZON_OFFSET_DEFAULT,
.camera_uptilt = SETTING_OSD_CAMERA_UPTILT_DEFAULT,
.ahi_camera_uptilt_comp = SETTING_OSD_AHI_CAMERA_UPTILT_COMP_DEFAULT,
.camera_fov_h = SETTING_OSD_CAMERA_FOV_H_DEFAULT,
.camera_fov_v = SETTING_OSD_CAMERA_FOV_V_DEFAULT,
.hud_margin_h = SETTING_OSD_HUD_MARGIN_H_DEFAULT,
@ -2956,6 +3003,7 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig)
osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1);
osdLayoutsConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1);
osdLayoutsConfig->item_pos[0][OSD_3D_SPEED] = OSD_POS(23, 1);
osdLayoutsConfig->item_pos[0][OSD_GLIDESLOPE] = OSD_POS(23, 2);
osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS_AUTO_THR] = OSD_POS(6, 2);
@ -2981,17 +3029,17 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig)
// OSD_VARIO_NUM at the right of OSD_VARIO
osdLayoutsConfig->item_pos[0][OSD_VARIO_NUM] = OSD_POS(24, 7);
osdLayoutsConfig->item_pos[0][OSD_HOME_DIR] = OSD_POS(14, 11);
osdLayoutsConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6);
osdLayoutsConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6);
osdLayoutsConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2);
osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6);
#ifdef USE_SERIALRX_CRSF
osdLayoutsConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(24, 12);
osdLayoutsConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(24, 11);
osdLayoutsConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(25, 9);
osdLayoutsConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(25, 10);
osdLayoutsConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(23, 12);
osdLayoutsConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(23, 11);
osdLayoutsConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(24, 9);
osdLayoutsConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(24, 10);
#endif
osdLayoutsConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8);
@ -3828,7 +3876,7 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
// Countdown display for remaining Waypoints
char buf[6];
osdFormatDistanceSymbol(buf, posControl.wpDistance, 0);
tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", posControl.activeWaypointIndex + 1, posControl.waypointCount, buf);
tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", getGeoWaypointNumber(posControl.activeWaypointIndex), posControl.geoWaypointCount, buf);
messages[messageCount++] = messageBuf;
} else if (NAV_Status.state == MW_NAV_STATE_HOLD_TIMED) {
// WP hold time countdown in seconds
@ -3864,7 +3912,7 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
// by OSD_FLYMODE.
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ALTITUDE_HOLD);
}
if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) {
if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM) && !feature(FEATURE_FW_AUTOTRIM)) {
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTRIM);
}
if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE)) {

View file

@ -231,6 +231,7 @@ typedef enum {
OSD_PLIMIT_REMAINING_BURST_TIME,
OSD_PLIMIT_ACTIVE_CURRENT_LIMIT,
OSD_PLIMIT_ACTIVE_POWER_LIMIT,
OSD_GLIDESLOPE,
OSD_ITEM_COUNT // MUST BE LAST
} osd_items_e;
@ -312,6 +313,7 @@ typedef struct osdConfig_s {
#ifdef USE_SERIALRX_CRSF
int8_t snr_alarm; //CRSF SNR alarm in dB
int8_t link_quality_alarm;
int16_t rssi_dbm_alarm; // in dBm
#endif
#ifdef USE_BARO
int16_t baro_temp_alarm_min;
@ -331,6 +333,7 @@ typedef struct osdConfig_s {
uint8_t crosshairs_style; // from osd_crosshairs_style_e
int8_t horizon_offset;
int8_t camera_uptilt;
bool ahi_camera_uptilt_comp;
uint8_t camera_fov_h;
uint8_t camera_fov_v;
uint8_t hud_margin_h;

View file

@ -186,6 +186,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
.launch_throttle = SETTING_NAV_FW_LAUNCH_THR_DEFAULT,
.launch_idle_throttle = SETTING_NAV_FW_LAUNCH_IDLE_THR_DEFAULT, // Motor idle or MOTOR_STOP
.launch_motor_timer = SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT, // ms
.launch_idle_motor_timer = SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT, // ms
.launch_motor_spinup_time = SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT, // ms, time to gredually increase throttle from idle to launch
.launch_end_time = SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode
.launch_min_time = SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT, // ms, min time in launch mode
@ -1727,7 +1728,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_WAIT(navigationF
//allow to leave NAV_LAUNCH_MODE if it has being enabled as feature by moving sticks with low throttle.
if (feature(FEATURE_FW_LAUNCH)) {
throttleStatus_e throttleStatus = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC);
if ((throttleStatus == THROTTLE_LOW) && (areSticksDeflectedMoreThanPosHoldDeadband())) {
if ((throttleStatus == THROTTLE_LOW) && (isRollPitchStickDeflected())) {
abortFixedWingLaunch();
return NAV_FSM_EVENT_SWITCH_TO_IDLE;
}
@ -2832,13 +2833,23 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData)
else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS) && !ARMING_FLAG(ARMED)) {
if (wpData->action == NAV_WP_ACTION_WAYPOINT || wpData->action == NAV_WP_ACTION_JUMP || wpData->action == NAV_WP_ACTION_RTH || wpData->action == NAV_WP_ACTION_HOLD_TIME || wpData->action == NAV_WP_ACTION_LAND || wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD ) {
// Only allow upload next waypoint (continue upload mission) or first waypoint (new mission)
static int8_t nonGeoWaypointCount = 0;
if (wpNumber == (posControl.waypointCount + 1) || wpNumber == 1) {
posControl.waypointList[wpNumber - 1] = *wpData;
if(wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD || wpData->action == NAV_WP_ACTION_JUMP) {
nonGeoWaypointCount += 1;
if(wpData->action == NAV_WP_ACTION_JUMP) {
posControl.waypointList[wpNumber - 1].p1 -= 1; // make index (vice WP #)
}
}
posControl.waypointCount = wpNumber;
posControl.waypointListValid = (wpData->flag == NAV_WP_FLAG_LAST);
posControl.geoWaypointCount = posControl.waypointCount - nonGeoWaypointCount;
if (posControl.waypointListValid) {
nonGeoWaypointCount = 0;
}
}
}
}
@ -2850,6 +2861,7 @@ void resetWaypointList(void)
if (!ARMING_FLAG(ARMED)) {
posControl.waypointCount = 0;
posControl.waypointListValid = false;
posControl.geoWaypointCount = 0;
}
}

View file

@ -264,6 +264,7 @@ typedef struct navConfig_s {
uint16_t launch_idle_throttle; // Throttle to keep at launch idle
uint16_t launch_throttle; // Launch throttle
uint16_t launch_motor_timer; // Time to wait before setting launch_throttle (ms)
uint16_t launch_idle_motor_timer; // Time to wait before motor starts at_idle throttle (ms)
uint16_t launch_motor_spinup_time; // Time to speed-up motors from idle to launch_throttle (ESC desync prevention)
uint16_t launch_end_time; // Time to make the transition from launch angle to leveled and throttle transition from launch throttle to the stick position
uint16_t launch_min_time; // Minimum time in launch mode to prevent possible bump of the sticks from leaving launch mode early

View file

@ -54,6 +54,7 @@
#define LAUNCH_MOTOR_IDLE_SPINUP_TIME 1500 // ms
#define UNUSED(x) ((void)(x))
#define FW_LAUNCH_MESSAGE_TEXT_WAIT_THROTTLE "RAISE THE THROTTLE"
#define FW_LAUNCH_MESSAGE_TEXT_WAIT_IDLE "WAITING FOR IDLE"
#define FW_LAUNCH_MESSAGE_TEXT_WAIT_DETECTION "READY"
#define FW_LAUNCH_MESSAGE_TEXT_IN_PROGRESS "MOVE THE STICKS TO ABORT"
#define FW_LAUNCH_MESSAGE_TEXT_FINISHING "FINISHING"
@ -61,6 +62,7 @@
typedef enum {
FW_LAUNCH_MESSAGE_TYPE_NONE = 0,
FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE,
FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE,
FW_LAUNCH_MESSAGE_TYPE_WAIT_DETECTION,
FW_LAUNCH_MESSAGE_TYPE_IN_PROGRESS,
FW_LAUNCH_MESSAGE_TYPE_FINISHING
@ -78,6 +80,7 @@ typedef enum {
typedef enum {
FW_LAUNCH_STATE_IDLE = 0,
FW_LAUNCH_STATE_WAIT_THROTTLE,
FW_LAUNCH_STATE_IDLE_MOTOR_DELAY,
FW_LAUNCH_STATE_MOTOR_IDLE,
FW_LAUNCH_STATE_WAIT_DETECTION,
FW_LAUNCH_STATE_DETECTED,
@ -90,6 +93,7 @@ typedef enum {
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE(timeUs_t currentTimeUs);
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs_t currentTimeUs);
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(timeUs_t currentTimeUs);
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE(timeUs_t currentTimeUs);
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_DETECTION(timeUs_t currentTimeUs);
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_DETECTED(timeUs_t currentTimeUs);
@ -111,6 +115,7 @@ typedef struct fixedWingLaunchData_s {
} fixedWingLaunchData_t;
static EXTENDED_FASTRAM fixedWingLaunchData_t fwLaunch;
static bool idleMotorAboutToStart;
static const fixedWingLaunchStateDescriptor_t launchStateMachine[FW_LAUNCH_STATE_COUNT] = {
@ -125,19 +130,28 @@ static const fixedWingLaunchStateDescriptor_t launchStateMachine[FW_LAUNCH_STATE
[FW_LAUNCH_STATE_WAIT_THROTTLE] = {
.onEntry = fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE,
.onEvent = {
[FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_MOTOR_IDLE,
[FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_IDLE_MOTOR_DELAY,
[FW_LAUNCH_EVENT_GOTO_DETECTION] = FW_LAUNCH_STATE_WAIT_DETECTION
},
.messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE
},
[FW_LAUNCH_STATE_IDLE_MOTOR_DELAY] = {
.onEntry = fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY,
.onEvent = {
[FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_MOTOR_IDLE,
[FW_LAUNCH_EVENT_THROTTLE_LOW] = FW_LAUNCH_STATE_WAIT_THROTTLE
},
.messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE
},
[FW_LAUNCH_STATE_MOTOR_IDLE] = {
.onEntry = fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE,
.onEvent = {
[FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_WAIT_DETECTION,
[FW_LAUNCH_EVENT_THROTTLE_LOW] = FW_LAUNCH_STATE_WAIT_THROTTLE
},
.messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE
.messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE
},
[FW_LAUNCH_STATE_WAIT_DETECTION] = {
@ -237,7 +251,7 @@ static inline bool isLaunchMaxAltitudeReached(void)
static inline bool areSticksMoved(timeMs_t initialTime, timeUs_t currentTimeUs)
{
return (initialTime + currentStateElapsedMs(currentTimeUs)) > navConfig()->fw.launch_min_time && areSticksDeflectedMoreThanPosHoldDeadband();
return (initialTime + currentStateElapsedMs(currentTimeUs)) > navConfig()->fw.launch_min_time && isRollPitchStickDeflected();
}
static void resetPidsIfNeeded(void) {
@ -287,6 +301,24 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs
return FW_LAUNCH_EVENT_NONE;
}
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(timeUs_t currentTimeUs)
{
if (isThrottleLow()) {
return FW_LAUNCH_EVENT_THROTTLE_LOW; // go back to FW_LAUNCH_STATE_WAIT_THROTTLE
}
applyThrottleIdleLogic(true);
if (currentStateElapsedMs(currentTimeUs) > navConfig()->fw.launch_idle_motor_timer) {
idleMotorAboutToStart = false;
return FW_LAUNCH_EVENT_SUCCESS;
}
// 5 second warning motor about to start at idle, changes Beeper sound
idleMotorAboutToStart = navConfig()->fw.launch_idle_motor_timer - currentStateElapsedMs(currentTimeUs) < 5000;
return FW_LAUNCH_EVENT_NONE;
}
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE(timeUs_t currentTimeUs)
{
if (isThrottleLow()) {
@ -403,7 +435,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_FINISH(timeUs_t curr
const timeMs_t elapsedTimeMs = currentStateElapsedMs(currentTimeUs);
const timeMs_t endTimeMs = navConfig()->fw.launch_end_time;
if (areSticksDeflectedMoreThanPosHoldDeadband()) {
if (isRollPitchStickDeflected()) {
return FW_LAUNCH_EVENT_ABORT; // cancel the launch and do the FW_LAUNCH_STATE_IDLE state
}
if (elapsedTimeMs > endTimeMs) {
@ -441,8 +473,12 @@ void applyFixedWingLaunchController(timeUs_t currentTimeUs)
beeper(BEEPER_LAUNCH_MODE_LOW_THROTTLE);
}
else {
if (idleMotorAboutToStart) {
beeper(BEEPER_LAUNCH_MODE_IDLE_START);
} else {
beeper(BEEPER_LAUNCH_MODE_ENABLED);
}
}
}
void resetFixedWingLaunchController(timeUs_t currentTimeUs)
@ -476,6 +512,9 @@ const char * fixedWingLaunchStateMessage(void)
case FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE:
return FW_LAUNCH_MESSAGE_TEXT_WAIT_THROTTLE;
case FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE:
return FW_LAUNCH_MESSAGE_TEXT_WAIT_IDLE;
case FW_LAUNCH_MESSAGE_TYPE_WAIT_DETECTION:
return FW_LAUNCH_MESSAGE_TEXT_WAIT_DETECTION;

1
src/main/navigation/navigation_private.h Executable file → Normal file
View file

@ -356,6 +356,7 @@ typedef struct {
navWaypoint_t waypointList[NAV_MAX_WAYPOINTS];
bool waypointListValid;
int8_t waypointCount;
int8_t geoWaypointCount; // total geospatial WPs in mission
navWaypointPosition_t activeWaypoint; // Local position and initial bearing, filled on waypoint activation
int8_t activeWaypointIndex;

View file

@ -19,6 +19,7 @@
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
#define MAVLINK_COMM_NUM_BUFFERS 1
#include "common/mavlink.h"
#pragma GCC diagnostic pop

View file

@ -299,7 +299,9 @@ void FAST_CODE NOINLINE scheduler(void)
#if defined(SCHEDULER_DEBUG)
DEBUG_SET(DEBUG_SCHEDULER, 2, micros() - currentTimeUs - taskExecutionTime); // time spent in scheduler
#endif
} else {
}
if (!selectedTask || forcedRealTimeTask) {
// Execute system real-time callbacks and account for them to SYSTEM account
const timeUs_t currentTimeBeforeTaskCall = micros();
taskRunRealtimeCallbacks(currentTimeBeforeTaskCall);

View file

@ -329,6 +329,16 @@ bool compassIsReady(void)
return magUpdatedAtLeastOnce;
}
bool compassIsCalibrationComplete(void)
{
if (STATE(COMPASS_CALIBRATED)) {
return true;
}
else {
return false;
}
}
void compassUpdate(timeUs_t currentTimeUs)
{
static sensorCalibrationState_t calState;

View file

@ -78,5 +78,6 @@ bool compassInit(void);
void compassUpdate(timeUs_t currentTimeUs);
bool compassIsReady(void);
bool compassIsHealthy(void);
bool compassIsCalibrationComplete(void);
#endif

View file

@ -111,7 +111,7 @@ STATIC_FASTRAM alphaBetaGammaFilter_t abgFilter[XYZ_AXIS_COUNT];
#endif
PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 13);
PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 14);
PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig,
.gyro_lpf = SETTING_GYRO_HARDWARE_LPF_DEFAULT,

View file

@ -63,7 +63,7 @@ typedef struct gyroConfig_s {
uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
uint16_t looptime; // imu loop time in us
uint8_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
uint8_t gyro_anti_aliasing_lpf_hz;
uint16_t gyro_anti_aliasing_lpf_hz;
uint8_t gyro_anti_aliasing_lpf_type;
#ifdef USE_DUAL_GYRO
uint8_t gyro_to_use;

View file

@ -0,0 +1,2 @@
target_stm32f745xg(FLYWOOF745)
target_stm32f745xg(FLYWOOF745NANO)

View file

@ -0,0 +1,45 @@
/*
* This file is part of INAV.
*
* 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 <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/bus.h"
const timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 , DMA1_ST7
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M2 , DMA1_ST2
DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // M3 , DMA2_ST2
DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // M4 , DMA2_ST4
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M5 , DMA2_ST7
DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M6 , DMA1_ST1
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M7 , DMA1_ST4
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M8 , DMA1_ST5
DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_STRIP, DMA1_ST0
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,187 @@
/*
* This file is part of INAV.
*
* 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
#ifdef FLYWOOF745
#define TARGET_BOARD_IDENTIFIER "FWF7"
#define USBD_PRODUCT_STRING "FLYWOOF745"
#else
#define TARGET_BOARD_IDENTIFIER "FW7N"
#define USBD_PRODUCT_STRING "FLYWOOF745NANO"
#endif
#define LED0 PA2//
#define BEEPER PD15//
#define BEEPER_INVERTED
#define USE_DSHOT
#define USE_ESC_SENSOR
#define USE_MPU_DATA_READY_SIGNAL
#define USE_EXTI
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW270_DEG//
#define GYRO_INT_EXTI PE1//
#define MPU6000_CS_PIN SPI4_NSS_PIN//
#define MPU6000_SPI_BUS BUS_SPI4//
#define USB_IO
#define USE_VCP
#define VBUS_SENSING_ENABLED
#define VBUS_SENSING_PIN PA8//
#define USE_UART1
#define UART1_TX_PIN PA9//
#define UART1_RX_PIN PA10//
#define USE_UART2
#define UART2_TX_PIN PD5//
#define UART2_RX_PIN PD6//
#define USE_UART3
#ifdef FLYWOOF745
#define UART3_TX_PIN PB10//
#define UART3_RX_PIN PB11//
#else
#define UART3_TX_PIN PD8//
#define UART3_RX_PIN PD9//
#endif
#define USE_UART4
#define UART4_TX_PIN PA0//
#define UART4_RX_PIN PA1//
#define USE_UART5
#define UART5_TX_PIN PC12//
#define UART5_RX_PIN PD2//
#define USE_UART6
#define UART6_TX_PIN PC6//
#define UART6_RX_PIN PC7//
#define USE_UART7
#define UART7_TX_PIN PE8//
#define UART7_RX_PIN PE7//
#define SERIAL_PORT_COUNT 8 //VCP,UART1,UART2,UART3,UART4,UART5,UART6,UART7
#define USE_SPI
#define USE_SPI_DEVICE_1 //FLASH
#define USE_SPI_DEVICE_2 //OSD
#define USE_SPI_DEVICE_4 //ICM20689
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define SPI4_NSS_PIN PE4
#define SPI4_SCK_PIN PE2
#define SPI4_MISO_PIN PE5
#define SPI4_MOSI_PIN PE6
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN SPI2_NSS_PIN
#define M25P16_CS_PIN SPI1_NSS_PIN
#define M25P16_SPI_BUS BUS_SPI1
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#ifdef FLYWOOF745NANO
#define USE_I2C_DEVICE_2
#define I2C2_SCL PB10
#define I2C2_SDA PB11
//External I2C bus is different than internal one
#define MAG_I2C_BUS BUS_I2C2
#define TEMPERATURE_I2C_BUS BUS_I2C2
#define RANGEFINDER_I2C_BUS BUS_I2C2
#define DEFAULT_I2C_BUS BUS_I2C2
#else
//External I2C bus is the same as interal one
#define MAG_I2C_BUS BUS_I2C1
#define TEMPERATURE_I2C_BUS BUS_I2C1
#define RANGEFINDER_I2C_BUS BUS_I2C1
#define DEFAULT_I2C_BUS BUS_I2C1
#endif
#define USE_BARO
#define USE_BARO_BMP280
#define BARO_I2C_BUS BUS_I2C1
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_MAG3110
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_LIS3MDL
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC2
#define ADC_CHANNEL_2_PIN PC3
#define ADC_CHANNEL_3_PIN PC5
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
#define VBAT_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_VBAT | FEATURE_BLACKBOX)
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_UART SERIAL_PORT_USART1
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define USE_LED_STRIP
#define WS2811_PIN PD12 // //TIM4_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 0xffff
#define TARGET_IO_PORTE 0xffff
#define MAX_PWM_OUTPUT_PORTS 8

View file

@ -1,2 +1,3 @@
target_stm32f722xe(MATEKF722SE)
target_stm32f722xe(MATEKF722MINI)
target_stm32f722xe(MATEKF722SE_8MOTOR)

View file

@ -38,8 +38,13 @@ const timerHardware_t timerHardware[] = {
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2
DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3)
#if (defined(MATEKF722SE_8MOTOR))
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 UP1-6 D(1, 0, 2)
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 UP1-6 D(1, 3, 2)
#else
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S7 UP1-6 D(1, 0, 2)
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S8 UP1-6 D(1, 3, 2)
#endif
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 6, 0)

View file

@ -29,25 +29,22 @@
BUSDEV_REGISTER_SPI_TAG(busdev_imu1_6000, DEVHW_MPU6000, IMU1_SPI_BUS, IMU1_CS_PIN, IMU1_EXTI_PIN, 0, DEVFLAGS_NONE, IMU1_ALIGN);
BUSDEV_REGISTER_SPI_TAG(busdev_imu2_6500, DEVHW_MPU6500, IMU2_SPI_BUS, IMU2_CS_PIN, IMU2_EXTI_PIN, 1, DEVFLAGS_NONE, IMU2_ALIGN);
//BUSDEV_REGISTER_SPI_TAG(busdev_imu1_6500, DEVHW_MPU6500, IMU1_SPI_BUS, IMU1_CS_PIN, IMU1_EXTI_PIN, 0, DEVFLAGS_NONE, IMU1_ALIGN);
//BUSDEV_REGISTER_SPI_TAG(busdev_imu2_6000, DEVHW_MPU6000, IMU2_SPI_BUS, IMU2_CS_PIN, IMU2_EXTI_PIN, 1, DEVFLAGS_NONE, IMU2_ALIGN);
const timerHardware_t timerHardware[] = {
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 2), // S1
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 2), // S2
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4
DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5
DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S3
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 4), // S4
DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 5), // S5
DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 6), // S6
DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S7
DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S8
DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S9
DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 7), // S7
DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 8), // S8
DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9
DEF_TIM(TIM4, CH4, PD15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 DMA_NONE
DEF_TIM(TIM15, CH1, PE5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S11
DEF_TIM(TIM15, CH2, PE6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S12
DEF_TIM(TIM15, CH1, PE5, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11
DEF_TIM(TIM15, CH2, PE6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S12 DMA_NONE
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED_2812
DEF_TIM(TIM2, CH1, PA15, TIM_USE_BEEPER, 0, 0), // BEEPER PWM

View file

@ -18,8 +18,8 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "H765"
#define USBD_PRODUCT_STRING "MATEKH765"
#define TARGET_BOARD_IDENTIFIER "H743"
#define USBD_PRODUCT_STRING "MATEKH743"
#define LED0 PE3
#define LED1 PE4
@ -27,9 +27,6 @@
#define BEEPER PA15
#define BEEPER_INVERTED
// *************** UART *****************************
#define USE_VCP
@ -67,23 +64,13 @@
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART6
#define MAX_PWM_OUTPUT_PORTS 15
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
// *************** IMU generic ***********************
#define USE_DUAL_GYRO
#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
// *************** SPI1 IMU1 *************************
#define USE_SPI
#define USE_SPI_DEVICE_1
@ -105,12 +92,10 @@
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
/*
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
*/
// *************** SPI3 SD BLACKBOX*******************
/*
@ -146,6 +131,7 @@
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_DPS310
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
@ -163,20 +149,16 @@
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS BUS_I2C2
#if 0
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC_CHANNEL_1_PIN PC2
#define ADC_CHANNEL_2_PIN PC3
#define ADC_CHANNEL_3_PIN PC1
#define ADC_CHANNEL_4_PIN PC0
#define ADC_CHANNEL_1_PIN PC0 //ADC123 VBAT1
#define ADC_CHANNEL_2_PIN PC1 //ADC123 CURR1
#define ADC_CHANNEL_3_PIN PC5 //ADC12 RSSI
#define ADC_CHANNEL_4_PIN PC4 //ADC12 AirS
#define ADC_CHANNEL_5_PIN PA4 //ADC12 VB2
#define ADC_CHANNEL_6_PIN PA7 //ADC12 CU2
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
@ -198,7 +180,13 @@
#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 0xffff
#define TARGET_IO_PORTE 0xffff
#define MAX_PWM_OUTPUT_PORTS 15
#define USE_DSHOT
#define USE_ESC_SENSOR
#define USE_SERIALSHOT
#endif

View file

@ -1,55 +0,0 @@
/*
*****************************************************************************
**
** File : stm32_flash_f765.ld
**
** Abstract : Linker script for STM32F765xITx Device with
** 2048KByte FLASH, 512KByte RAM
**
*****************************************************************************
*/
/* Stack & Heap sizes */
_Min_Heap_Size = 0;
_Min_Stack_Size = 0x1800;
/* Entry Point */
ENTRY(Reset_Handler)
/*
0x00000000 to 0x00003FFF 16K TCM RAM,
0x08000000 to 0x081FFFFF 2048K full flash,
0x08000000 to 0x08007FFF 32K isr vector, startup code,
0x08008000 to 0x0800FFFF 32K config,
0x08010000 to 0x081FFFFF 1984K firmware,
*/
/* Specify the memory areas */
MEMORY
{
ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K
ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K
ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K
ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
AXIM_FLASH_CFG (r) : ORIGIN = 0x08008000, LENGTH = 32K
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 1984K
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K
SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
REGION_ALIAS("FLASH", AXIM_FLASH)
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG)
REGION_ALIAS("FLASH1", AXIM_FLASH1)
REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_RAM)
REGION_ALIAS("RAM", SRAM1)
INCLUDE "stm32_flash_f7_split.ld"

View file

@ -1,56 +0,0 @@
/*
*****************************************************************************
**
** File : stm32_flash_f765.ld
**
** Abstract : Linker script for STM32F765xITx Device with
** 2048KByte FLASH, 512KByte RAM
**
*****************************************************************************
*/
/* Stack & Heap sizes */
_Min_Heap_Size = 0;
_Min_Stack_Size = 0x1800;
/* Entry Point */
ENTRY(Reset_Handler)
/*
0x00000000 to 0x00003FFF 16K TCM RAM,
0x08000000 to 0x081FFFFF 2048K full flash,
0x08000000 to 0x08007FFF 32K isr vector, startup code,
0x08008000 to 0x0800FFFF 32K config,
0x08010000 to 0x081FFFFF 1984K firmware,
*/
/* Specify the memory areas */
MEMORY
{
ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K
ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K
ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K
ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
AXIM_FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 32K
AXIM_FLASH_CFG (r) : ORIGIN = 0x08010000, LENGTH = 32K
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K
SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
REGION_ALIAS("FLASH", AXIM_FLASH)
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG)
REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_RAM)
REGION_ALIAS("RAM", SRAM1)
__firmware_start = ORIGIN(AXIM_FIRMWARE);
INCLUDE "stm32_flash_f7.ld"

View file

@ -1,57 +0,0 @@
/*
*****************************************************************************
**
** File : stm32_flash_f765.ld
**
** Abstract : Linker script for STM32F765xITx Device with
** 2048KByte FLASH, 512KByte RAM
**
*****************************************************************************
*/
/* Stack & Heap sizes */
_Min_Heap_Size = 0;
_Min_Stack_Size = 0x1800;
/* Entry Point */
ENTRY(Reset_Handler)
/*
0x00000000 to 0x00003FFF 16K TCM RAM,
0x08000000 to 0x081FFFFF 2048K full flash,
0x08000000 to 0x08007FFF 32K isr vector, startup code,
0x08008000 to 0x0800FFFF 32K config,
0x08010000 to 0x081FFFFF 1984K firmware,
*/
/* Specify the memory areas */
MEMORY
{
ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K
ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K
ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K
ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K
AXIM_FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 32K
AXIM_FLASH_CFG (r) : ORIGIN = 0x08010000, LENGTH = 32K
AXIM_FLASH1 (rx) : ORIGIN = 0x08018000, LENGTH = 1984K
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K
SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
REGION_ALIAS("FLASH", AXIM_FLASH)
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG)
REGION_ALIAS("FLASH1", AXIM_FLASH1)
REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_RAM)
REGION_ALIAS("RAM", SRAM1)
__firmware_start = ORIGIN(AXIM_FLASH);
INCLUDE "stm32_flash_f7_split.ld"

View file

@ -89,6 +89,7 @@
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
#define MAVLINK_COMM_NUM_BUFFERS 1
#include "common/mavlink.h"
#pragma GCC diagnostic pop
@ -326,7 +327,14 @@ void checkMAVLinkTelemetryState(void)
static void mavlinkSendMessage(void)
{
uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN];
if (telemetryConfig()->mavlink.version == 1) mavSendMsg.magic = MAVLINK_STX_MAVLINK1;
mavlink_status_t* chan_state = mavlink_get_channel_status(MAVLINK_COMM_0);
if (telemetryConfig()->mavlink.version == 1) {
chan_state->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
} else {
chan_state->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
}
int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavSendMsg);
for (int i = 0; i < msgLength; i++) {
@ -502,8 +510,9 @@ void mavlinkSendRCChannelsAndRSSI(void)
GET_CHANNEL_VALUE(6),
// chan8_raw RC channel 8 value, in microseconds
GET_CHANNEL_VALUE(7),
// rssi Receive signal strength indicator, 0: 0%, 255: 100%
scaleRange(getRSSI(), 0, 1023, 0, 255));
// rssi Receive signal strength indicator, 0: 0%, 254: 100%
//https://github.com/mavlink/mavlink/issues/1027
scaleRange(getRSSI(), 0, 1023, 0, 254));
#undef GET_CHANNEL_VALUE
mavlinkSendMessage();
@ -733,7 +742,7 @@ void mavlinkSendHUDAndHeartbeat(void)
mavSystemState = MAV_STATE_ACTIVE;
}
}
else if (isCalibrating()) {
else if (areSensorsCalibrating()) {
mavSystemState = MAV_STATE_CALIBRATING;
}
else {

View file

@ -907,8 +907,8 @@ class Generator
unsigned = !$~[:unsigned].empty?
bitsize = $~[:bitsize].to_i
type_range = unsigned ? 0..(2**bitsize-1) : (-2**(bitsize-1)+1)..(2**(bitsize-1)-1)
min = type_range.min if min =~ /\AU?INT\d+_MIN\Z/
max = type_range.max if max =~ /\AU?INT\d+_MAX\Z/
min = type_range.min if min.to_s =~ /\AU?INT\d+_MIN\Z/
max = type_range.max if max.to_s =~ /\AU?INT\d+_MAX\Z/
raise "Member #{name} default value has an invalid type, integer or symbol expected" unless default_value.is_a? Integer or default_value.is_a? Symbol
raise "Member #{name} default value is outside type's storage range, min #{type_range.min}, max #{type_range.max}" unless default_value.is_a? Symbol or type_range === default_value
raise "Numeric member #{name} doesn't have maximum value defined" unless member.has_key? 'max'

View file

@ -38,7 +38,7 @@ def parse_settings_yaml():
with open(SETTINGS_YAML_PATH, "r") as settings_yaml:
return yaml.load(settings_yaml, Loader=yaml.Loader)
def generate_md_table_from_yaml(settings_yaml):
def generate_md_from_yaml(settings_yaml):
"""Generate a sorted markdown table with description & default value for each setting"""
params = {}
@ -84,20 +84,19 @@ def generate_md_table_from_yaml(settings_yaml):
"max": member["max"] if "max" in member else ""
}
# MD table header
md_table_lines = [
"| Variable Name | Default Value | Min | Max | Description |\n",
"| ------------- | ------------- | --- | --- | ----------- |\n",
]
# Sort the settings by name and build the rows of the table
# Sort the settings by name and build the doc
output_lines = []
for param in sorted(params.items()):
md_table_lines.append("| {} | {} | {} | {} | {} |\n".format(
param[0], param[1]['default'], param[1]['min'], param[1]['max'], param[1]['description']
))
output_lines.extend([
f"### {param[0]}\n\n",
f"{param[1]['description'] if param[1]['description'] else '_// TODO_'}\n\n",
"| Default | Min | Max |\n| --- | --- | --- |\n",
f"| {param[1]['default']} | {param[1]['min']} | {param[1]['max']} |\n\n",
"---\n\n"
])
# Return the assembled table
return md_table_lines
# Return the assembled doc body
return output_lines
def write_settings_md(lines):
"""Write the contents of the CLI settings docs"""
@ -185,9 +184,9 @@ if __name__ == "__main__":
defaults_match = check_defaults(settings_yaml)
quit(0 if defaults_match else 1)
md_table_lines = generate_md_table_from_yaml(settings_yaml)
settings_md_lines = \
["# CLI Variable Reference\n", "\n" ] + \
md_table_lines + \
["\n", "> Note: this table is autogenerated. Do not edit it manually."]
write_settings_md(settings_md_lines)
output_lines = generate_md_from_yaml(settings_yaml)
output_lines = [
"# CLI Variable Reference\n\n",
"> Note: this document is autogenerated. Do not edit it manually.\n\n"
] + output_lines
write_settings_md(output_lines)