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

Merge branch 'master' of github.com:betaflight/betaflight into feature/f4-dma-osd

This commit is contained in:
nathan 2016-07-16 09:25:40 -07:00
commit 338d548e11
134 changed files with 1669 additions and 1624 deletions

View file

@ -548,8 +548,8 @@ VPATH := $(VPATH):$(STDPERIPH_DIR)/src
# Find out if ccache is installed on the system
CCACHE := ccache
RESULT = $(shell which $(CCACHE))
ifeq ($(RESULT),)
RESULT = $(shell (which $(CCACHE) > /dev/null 2>&1; echo $$?) )
ifneq ($(RESULT),0)
CCACHE :=
endif

View file

@ -1140,6 +1140,7 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("Firmware type:%s", "Cleanflight");
BLACKBOX_PRINT_HEADER_LINE("Firmware revision:Betaflight %s (%s) %s", FC_VERSION_STRING, shortGitRevision, targetName);
BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime);
BLACKBOX_PRINT_HEADER_LINE("Craft name:%s", masterConfig.name);
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle);
BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", masterConfig.escAndServoConfig.maxthrottle);
@ -1218,6 +1219,8 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband);
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", masterConfig.gyro_lpf);
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz:%d", (int)(masterConfig.gyro_soft_notch_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_q:%d", (int)(masterConfig.gyro_soft_notch_q * 10.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.acc_hardware);
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.baro_hardware);

View file

@ -56,24 +56,39 @@ float pt1FilterApply4(pt1Filter_t *filter, float input, uint8_t f_cut, float dT)
}
/* sets up a biquad Filter */
void biquadFilterInit(biquadFilter_t *filter, float filterCutFreq, uint32_t refreshRate)
void biquadFilterInitLPF(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate)
{
biquadFilterInit(filter, filterFreq, refreshRate, BIQUAD_Q, FILTER_LPF);
}
void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, filterType_e filterType)
{
const float sampleRate = 1 / ((float)refreshRate * 0.000001f);
// setup variables
const float omega = 2 * M_PI_FLOAT * filterCutFreq / sampleRate;
const float sampleRate = 1 / ((float)refreshRate * 0.000001f);
const float omega = 2 * M_PI_FLOAT * filterFreq / sampleRate;
const float sn = sinf(omega);
const float cs = cosf(omega);
//this is wrong, should be hyperbolic sine
//alpha = sn * sinf(M_LN2_FLOAT /2 * BIQUAD_BANDWIDTH * omega /sn);
const float alpha = sn / (2 * BIQUAD_Q);
const float alpha = sn / (2 * Q);
const float b0 = (1 - cs) / 2;
const float b1 = 1 - cs;
const float b2 = (1 - cs) / 2;
const float a0 = 1 + alpha;
const float a1 = -2 * cs;
const float a2 = 1 - alpha;
float b0, b1, b2, a0, a1, a2;
switch (filterType) {
case FILTER_LPF:
b0 = (1 - cs) / 2;
b1 = 1 - cs;
b2 = (1 - cs) / 2;
a0 = 1 + alpha;
a1 = -2 * cs;
a2 = 1 - alpha;
break;
case FILTER_NOTCH:
b0 = 1;
b1 = -2 * cs;
b2 = 1;
a0 = 1 + alpha;
a1 = -2 * cs;
a2 = 1 - alpha;
break;
}
// precompute the coefficients
filter->b0 = b0 / a0;

View file

@ -29,8 +29,13 @@ typedef struct biquadFilter_s {
float d1, d2;
} biquadFilter_t;
typedef enum {
FILTER_LPF,
FILTER_NOTCH
} filterType_e;
void biquadFilterInit(biquadFilter_t *filter, float filterCutFreq, uint32_t refreshRate);
void biquadFilterInitLPF(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate);
void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, filterType_e filterType);
float biquadFilterApply(biquadFilter_t *filter, float input);
void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT);

View file

@ -441,6 +441,7 @@ static void resetConf(void)
featureSet(FEATURE_VBAT);
#endif
masterConfig.version = EEPROM_CONF_VERSION;
masterConfig.mixerMode = MIXER_QUADX;
@ -455,6 +456,8 @@ static void resetConf(void)
masterConfig.gyro_sync_denom = 4;
#endif
masterConfig.gyro_soft_lpf_hz = 100;
masterConfig.gyro_soft_notch_hz = 0;
masterConfig.gyro_soft_notch_q = 5;
masterConfig.pid_process_denom = 2;
@ -657,6 +660,7 @@ static void resetConf(void)
targetConfiguration();
#endif
// copy first profile into remaining profile
for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));
@ -715,7 +719,7 @@ void activateConfig(void)
&currentProfile->pidProfile
);
gyroUseConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz);
gyroUseConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz, masterConfig.gyro_soft_notch_hz, masterConfig.gyro_soft_notch_q);
#ifdef TELEMETRY
telemetryUseConfig(&masterConfig.telemetryConfig);

View file

@ -24,6 +24,8 @@
#endif
#define MAX_RATEPROFILES 3
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
#define MAX_NAME_LENGTH 16
typedef enum {
FEATURE_RX_PPM = 1 << 0,

View file

@ -58,7 +58,9 @@ typedef struct master_t {
uint8_t acc_for_fast_looptime; // shorten acc processing time by using 1 out of 9 samples. For combination with fast looptimes.
uint16_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_sync_denom; // Gyro sample divider
uint8_t gyro_soft_lpf_hz; // Biqyad gyro lpf hz
uint8_t gyro_soft_lpf_hz; // Biquad gyro lpf hz
uint16_t gyro_soft_notch_hz; // Biquad gyro notch hz
uint8_t gyro_soft_notch_q; // Biquad gyro notch quality
uint16_t dcm_kp; // DCM filter proportional gain ( x 10000)
uint16_t dcm_ki; // DCM filter integral gain ( x 10000)
@ -161,6 +163,9 @@ typedef struct master_t {
uint8_t magic_ef; // magic number, should be 0xEF
uint8_t chk; // XOR checksum
char name[MAX_NAME_LENGTH+1];
} master_t;
extern master_t masterConfig;

View file

@ -50,5 +50,6 @@ typedef enum {
DEBUG_MIXER,
DEBUG_AIRMODE,
DEBUG_PIDLOOP,
DEBUG_NOTCH,
DEBUG_COUNT
} debugType_e;

View file

@ -24,9 +24,6 @@
#include "build_config.h"
#include "system.h"
#include "sensors/sensors.h" // FIXME dependency into the main code
#include "sensor.h"
#include "accgyro.h"
#include "adc.h"
@ -84,7 +81,6 @@ void adcInit(drv_adc_config_t *init)
UNUSED(init);
#endif
uint8_t i;
uint8_t configuredAdcChannels = 0;
memset(&adcConfig, 0, sizeof(adcConfig));
@ -117,9 +113,9 @@ void adcInit(drv_adc_config_t *init)
if (device == ADCINVALID)
return;
adcDevice_t adc = adcHardware[device];
const adcDevice_t adc = adcHardware[device];
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag)
continue;
@ -163,7 +159,7 @@ void adcInit(drv_adc_config_t *init)
ADC_Init(adc.ADCx, &ADC_InitStructure);
uint8_t rank = 1;
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].enabled) {
continue;
}

View file

@ -21,7 +21,6 @@
#include "platform.h"
#include "system.h"
#include "common/utils.h"
#include "gpio.h"
#include "sensor.h"
@ -32,6 +31,8 @@
#include "io.h"
#include "rcc.h"
#include "common/utils.h"
#ifndef ADC_INSTANCE
#define ADC_INSTANCE ADC1
#endif
@ -100,7 +101,6 @@ void adcInit(drv_adc_config_t *init)
ADC_InitTypeDef ADC_InitStructure;
DMA_InitTypeDef DMA_InitStructure;
uint8_t i;
uint8_t adcChannelCount = 0;
memset(&adcConfig, 0, sizeof(adcConfig));
@ -135,7 +135,7 @@ void adcInit(drv_adc_config_t *init)
adcDevice_t adc = adcHardware[device];
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag)
continue;
@ -203,7 +203,7 @@ void adcInit(drv_adc_config_t *init)
ADC_Init(adc.ADCx, &ADC_InitStructure);
uint8_t rank = 1;
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].enabled) {
continue;
}

View file

@ -26,8 +26,6 @@
#include "io_impl.h"
#include "rcc.h"
#include "sensors/sensors.h" // FIXME dependency into the main code
#include "sensor.h"
#include "accgyro.h"

View file

@ -31,8 +31,6 @@
#define SPI_IO_AF_MOSI_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz)
#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_50MHz)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz)
#else
#error "Unknown processor"
#endif
/*

View file

@ -45,7 +45,6 @@ static dmaChannelDescriptor_t dmaDescriptors[] = {
DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream5, 38, DMA2_Stream5_IRQn, RCC_AHB1Periph_DMA2),
DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream6, 48, DMA2_Stream6_IRQn, RCC_AHB1Periph_DMA2),
DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream7, 54, DMA2_Stream7_IRQn, RCC_AHB1Periph_DMA2),
};
/*
@ -68,7 +67,6 @@ DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_ST5_HANDLER)
DEFINE_DMA_IRQ_HANDLER(2, 6, DMA2_ST6_HANDLER)
DEFINE_DMA_IRQ_HANDLER(2, 7, DMA2_ST7_HANDLER)
void dmaInit(void)
{
// TODO: Do we need this?

View file

@ -78,15 +78,14 @@ uint8_t ledPolarity = 0
#endif
;
uint8_t ledOffset = 0;
static uint8_t ledOffset = 0;
void ledInit(bool alternative_led)
{
uint32_t i;
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
if (alternative_led)
if (alternative_led) {
ledOffset = LED_NUMBER;
}
#else
UNUSED(alternative_led);
#endif
@ -95,7 +94,7 @@ void ledInit(bool alternative_led)
LED1_OFF;
LED2_OFF;
for (i = 0; i < LED_NUMBER; i++) {
for (int i = 0; i < LED_NUMBER; i++) {
if (leds[i + ledOffset]) {
IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i));
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
@ -114,6 +113,6 @@ void ledToggle(int led)
void ledSet(int led, bool on)
{
bool inverted = (1 << (led + ledOffset)) & ledPolarity;
const bool inverted = (1 << (led + ledOffset)) & ledPolarity;
IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
}

View file

@ -30,11 +30,6 @@
#include "pwm_rx.h"
#include "pwm_mapping.h"
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate);
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
/*
Configuration maps
@ -313,14 +308,14 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
}
#endif
if (init->useFastPwm) {
pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->idlePulse);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ;
pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse, init->pwmProtocolType);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_OUTPUT_PROTOCOL_ONESHOT;
} else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) {
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_MOTOR_MODE_BRUSHED | PWM_PF_OUTPUT_PROTOCOL_PWM;
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_MOTOR_MODE_BRUSHED;
} else {
pwmBrushlessMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM ;
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM;
}
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].index = pwmOutputConfiguration.motorCount;
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].timerHardware = timerHardwarePtr;

View file

@ -30,24 +30,8 @@
#error Invalid motor/servo/port configuration
#endif
#define PULSE_1MS (1000) // 1ms pulse width
#define MAX_INPUTS 8
#define PWM_TIMER_MHZ 1
#if defined(STM32F40_41xxx) // must be multiples of timer clock
#define ONESHOT42_TIMER_MHZ 21
#define ONESHOT125_TIMER_MHZ 12
#define PWM_BRUSHED_TIMER_MHZ 21
#define MULTISHOT_TIMER_MHZ 84
#else
#define PWM_BRUSHED_TIMER_MHZ 24
#define MULTISHOT_TIMER_MHZ 72
#define ONESHOT42_TIMER_MHZ 24
#define ONESHOT125_TIMER_MHZ 8
#endif
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5)
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
typedef struct sonarIOConfig_s {
ioTag_t triggerTag;

View file

@ -17,21 +17,31 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <math.h>
#include "platform.h"
#include "io.h"
#include "timer.h"
#include "flight/failsafe.h" // FIXME dependency into the main code from a driver
#include "pwm_mapping.h"
#include "pwm_output.h"
#if defined(STM32F40_41xxx) // must be multiples of timer clock
#define ONESHOT125_TIMER_MHZ 12
#define ONESHOT42_TIMER_MHZ 21
#define MULTISHOT_TIMER_MHZ 84
#define PWM_BRUSHED_TIMER_MHZ 21
#else
#define ONESHOT125_TIMER_MHZ 8
#define ONESHOT42_TIMER_MHZ 24
#define MULTISHOT_TIMER_MHZ 72
#define PWM_BRUSHED_TIMER_MHZ 24
#endif
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5)
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors
typedef struct {
@ -52,6 +62,8 @@ static pwmOutputPort_t *servos[MAX_PWM_SERVOS];
static uint8_t allocatedOutputPortCount = 0;
static bool pwmMotorsEnabled = true;
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t ouputPolarity)
{
TIM_OCInitTypeDef TIM_OCInitStructure;
@ -90,7 +102,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
configTimeBase(timerHardware->tim, period, mhz);
IO_t io = IOGetByTag(timerHardware->tag);
const IO_t io = IOGetByTag(timerHardware->tag);
IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount);
IOConfigGPIO(io, IOCFG_AF_PP);
@ -133,16 +145,16 @@ static void pwmWriteStandard(uint8_t index, uint16_t value)
*motors[index]->ccr = value;
}
static void pwmWriteOneShot42(uint8_t index, uint16_t value)
{
*motors[index]->ccr = lrintf((float)(value * ONESHOT42_TIMER_MHZ/24.0f));
}
static void pwmWriteOneShot125(uint8_t index, uint16_t value)
{
*motors[index]->ccr = lrintf((float)(value * ONESHOT125_TIMER_MHZ/8.0f));
}
static void pwmWriteOneShot42(uint8_t index, uint16_t value)
{
*motors[index]->ccr = lrintf((float)(value * ONESHOT42_TIMER_MHZ/24.0f));
}
static void pwmWriteMultiShot(uint8_t index, uint16_t value)
{
*motors[index]->ccr = lrintf(((float)(value-1000) * MULTISHOT_20US_MULT) + MULTISHOT_5US_PW);
@ -150,15 +162,14 @@ static void pwmWriteMultiShot(uint8_t index, uint16_t value)
void pwmWriteMotor(uint8_t index, uint16_t value)
{
if (motors[index] && index < MAX_MOTORS && pwmMotorsEnabled)
if (motors[index] && index < MAX_MOTORS && pwmMotorsEnabled) {
motors[index]->pwmWritePtr(index, value);
}
}
void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
{
uint8_t index;
for(index = 0; index < motorCount; index++){
for(int index = 0; index < motorCount; index++){
// Set the compare register to 0, which stops the output pulsing if the timer overflows
*motors[index]->ccr = 0;
}
@ -176,17 +187,14 @@ void pwmEnableMotors(void)
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
{
uint8_t index;
TIM_TypeDef *lastTimerPtr = NULL;
for (index = 0; index < motorCount; index++) {
for (int index = 0; index < motorCount; index++) {
// Force the timer to overflow if it's the first motor to output, or if we change timers
if (motors[index]->tim != lastTimerPtr) {
lastTimerPtr = motors[index]->tim;
timerForceOverflow(motors[index]->tim);
}
// Set the compare register to 0, which stops the output pulsing if the timer overflows before the main loop completes again.
// This compare register will be set to the output value on the next main loop.
*motors[index]->ccr = 0;
@ -195,44 +203,46 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate)
{
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
const uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, 0);
motors[motorIndex]->pwmWritePtr = pwmWriteBrushed;
}
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
{
uint32_t hz = PWM_TIMER_MHZ * 1000000;
const uint32_t hz = PWM_TIMER_MHZ * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, hz / motorPwmRate, idlePulse);
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
}
void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse)
void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, uint8_t fastPwmProtocolType)
{
uint32_t timerMhzCounter;
pwmWriteFuncPtr pwmWritePtr;
switch (fastPwmProtocolType) {
default:
case (PWM_TYPE_ONESHOT125):
timerMhzCounter = ONESHOT125_TIMER_MHZ;
pwmWritePtr = pwmWriteOneShot125;
break;
case (PWM_TYPE_ONESHOT42):
timerMhzCounter = ONESHOT42_TIMER_MHZ;
pwmWritePtr = pwmWriteOneShot42;
break;
case (PWM_TYPE_MULTISHOT):
timerMhzCounter = MULTISHOT_TIMER_MHZ;
pwmWritePtr = pwmWriteMultiShot;
break;
}
if (motorPwmRate > 0) {
uint32_t hz = timerMhzCounter * 1000000;
const uint32_t hz = timerMhzCounter * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, hz / motorPwmRate, idlePulse);
} else {
motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, 0xFFFF, 0);
}
motors[motorIndex]->pwmWritePtr = (fastPwmProtocolType == PWM_TYPE_MULTISHOT) ? pwmWriteMultiShot :
((fastPwmProtocolType == PWM_TYPE_ONESHOT125) ? pwmWriteOneShot125 :
pwmWriteOneShot42);
motors[motorIndex]->pwmWritePtr = pwmWritePtr;
}
#ifdef USE_SERVOS
@ -243,7 +253,8 @@ void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, ui
void pwmWriteServo(uint8_t index, uint16_t value)
{
if (servos[index] && index < MAX_SERVOS)
if (servos[index] && index < MAX_SERVOS) {
*servos[index]->ccr = value;
}
}
#endif

View file

@ -25,6 +25,12 @@ typedef enum {
PWM_TYPE_BRUSHED
} motorPwmProtocolTypes_e;
struct timerHardware_s;
void pwmBrushedMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate);
void pwmBrushlessMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmFastPwmMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, uint8_t fastPwmProtocolType);
void pwmServoConfig(const struct timerHardware_s *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
void pwmWriteMotor(uint8_t index, uint16_t value);
void pwmShutdownPulsesForAllMotors(uint8_t motorCount);
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount);

View file

@ -1,7 +1,7 @@
#pragma once
#define RESOURCE_INDEX(x) x + 1
#define RESOURCE_INDEX(x) (x + 1)
typedef enum {
OWNER_FREE = 0,

View file

@ -376,6 +376,7 @@ void USART1_IRQHandler(void)
uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port);
uartIrqHandler(s);
}
#endif
#ifdef USE_UART2

View file

@ -956,7 +956,7 @@ void filterServos(void)
if (mixerConfig->servo_lowpass_enable) {
for (servoIdx = 0; servoIdx < MAX_SUPPORTED_SERVOS; servoIdx++) {
if (!servoFilterIsSet) {
biquadFilterInit(&servoFilter[servoIdx], mixerConfig->servo_lowpass_freq, targetPidLooptime);
biquadFilterInitLPF(&servoFilter[servoIdx], mixerConfig->servo_lowpass_freq, targetPidLooptime);
servoFilterIsSet = true;
}

View file

@ -119,6 +119,7 @@ void cliDumpRateProfile(uint8_t rateProfileIndex) ;
static void cliExit(char *cmdline);
static void cliFeature(char *cmdline);
static void cliMotor(char *cmdline);
static void cliName(char *cmdline);
static void cliPlaySound(char *cmdline);
static void cliProfile(char *cmdline);
static void cliRateProfile(char *cmdline);
@ -340,6 +341,7 @@ const clicmd_t cmdTable[] = {
#ifdef VTX
CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL, cliVtx),
#endif
CLI_COMMAND_DEF("name", "Name of craft", NULL, cliName),
};
#define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
@ -451,6 +453,7 @@ static const char * const lookupTableDebug[DEBUG_COUNT] = {
"MIXER",
"AIRMODE",
"PIDLOOP",
"NOTCH",
};
#ifdef OSD
static const char * const lookupTableOsdType[] = {
@ -696,6 +699,8 @@ const clivalue_t valueTable[] = {
{ "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } },
{ "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } },
{ "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 255 } },
{ "gyro_notch_hz", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_hz, .config.minmax = { 0, 500 } },
{ "gyro_notch_q", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_notch_q, .config.minmax = { 1, 100 } },
{ "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } },
{ "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
{ "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
@ -1953,6 +1958,8 @@ static void cliDump(char *cmdline)
cliPrint("\r\n# version\r\n");
cliVersion(NULL);
cliPrint("\r\n# name\r\n");
cliName(NULL);
cliPrint("\r\n# dump master\r\n");
cliPrint("\r\n# mixer\r\n");
@ -2494,6 +2501,18 @@ static void cliMotor(char *cmdline)
cliPrintf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]);
}
static void cliName(char *cmdline)
{
uint32_t len = strlen(cmdline);
if (len > 0) {
memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH));
}
cliPrintf("name %s\r\n", strlen(masterConfig.name) > 0 ? masterConfig.name : "-");
return;
}
static void cliPlaySound(char *cmdline)
{
#if FLASH_SIZE <= 64

View file

@ -659,7 +659,7 @@ static uint32_t packFlightModeFlags(void)
static bool processOutCommand(uint8_t cmdMSP)
{
uint32_t i;
uint8_t len;
#ifdef GPS
uint8_t wp_no;
int32_t lat = 0, lon = 0;
@ -750,6 +750,14 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize16(constrain(averageSystemLoadPercent, 0, 100));
break;
case MSP_NAME:
len = strlen(masterConfig.name);
headSerialReply(len);
for (uint8_t i=0; i<len; i++) {
serialize8(masterConfig.name[i]);
}
break;
case MSP_STATUS:
headSerialReply(11);
serialize16(cycleTime);
@ -1868,6 +1876,13 @@ static bool processInCommand(void)
masterConfig.baro_hardware = read8();
masterConfig.mag_hardware = read8();
break;
case MSP_SET_NAME:
memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
for (i = 0; i < MIN(MAX_NAME_LENGTH, currentPort->dataSize); i++) {
masterConfig.name[i] = read8();
}
break;
default:
// we do not know how to handle the (valid) message, indicate error MSP $M!
return false;

View file

@ -99,6 +99,10 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_BOARD_INFO 4 //out message
#define MSP_BUILD_INFO 5 //out message
#define MSP_NAME 10
#define MSP_SET_NAME 11
//
// MSP commands for Cleanflight original features
//
@ -147,6 +151,23 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_ARMING_CONFIG 61 //out message Returns auto_disarm_delay and disarm_kill_switch parameters
#define MSP_SET_ARMING_CONFIG 62 //in message Sets auto_disarm_delay and disarm_kill_switch parameters
//
// Baseflight MSP commands (if enabled they exist in Cleanflight)
//
#define MSP_RX_MAP 64 //out message get channel map (also returns number of channels total)
#define MSP_SET_RX_MAP 65 //in message set rx map, numchannels to set comes from MSP_RX_MAP
// FIXME - Provided for backwards compatibility with configurator code until configurator is updated.
// DEPRECATED - DO NOT USE "MSP_BF_CONFIG" and MSP_SET_BF_CONFIG. In Cleanflight, isolated commands already exist and should be used instead.
#define MSP_BF_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
#define MSP_SET_BF_CONFIG 67 //in message baseflight-specific settings save
#define MSP_REBOOT 68 //in message reboot settings
// DEPRECATED - Use MSP_BUILD_INFO instead
#define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion
#define MSP_DATAFLASH_SUMMARY 70 //out message - get description of dataflash chip
#define MSP_DATAFLASH_READ 71 //out message - get content of dataflash chip
#define MSP_DATAFLASH_ERASE 72 //in message - erase dataflash chip
@ -177,22 +198,6 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_VTX_CONFIG 88 //in message Get vtx settings
#define MSP_SET_VTX_CONFIG 89 //out message Set vtx settings
//
// Baseflight MSP commands (if enabled they exist in Cleanflight)
//
#define MSP_RX_MAP 64 //out message get channel map (also returns number of channels total)
#define MSP_SET_RX_MAP 65 //in message set rx map, numchannels to set comes from MSP_RX_MAP
// FIXME - Provided for backwards compatibility with configurator code until configurator is updated.
// DEPRECATED - DO NOT USE "MSP_BF_CONFIG" and MSP_SET_BF_CONFIG. In Cleanflight, isolated commands already exist and should be used instead.
#define MSP_BF_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
#define MSP_SET_BF_CONFIG 67 //in message baseflight-specific settings save
#define MSP_REBOOT 68 //in message reboot settings
// DEPRECATED - Use MSP_BUILD_INFO instead
#define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion
// Betaflight Additional Commands
#define MSP_PID_ADVANCED_CONFIG 90
#define MSP_SET_PID_ADVANCED_CONFIG 91

View file

@ -190,7 +190,7 @@ void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
if (!accFilterInitialised) {
if (accTargetLooptime) { /* Initialisation needs to happen once sample rate is known */
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInit(&accFilter[axis], accLpfCutHz, accTargetLooptime);
biquadFilterInitLPF(&accFilter[axis], accLpfCutHz, accTargetLooptime);
}
accFilterInitialised = true;
}

View file

@ -70,7 +70,7 @@ static void updateBatteryVoltage(void)
if (debugMode == DEBUG_BATTERY) debug[0] = vbatSample;
if (!vbatFilterIsInitialised) {
biquadFilterInit(&vbatFilter, VBATT_LPF_FREQ, 50000); //50HZ Update
biquadFilterInitLPF(&vbatFilter, VBATT_LPF_FREQ, 50000); //50HZ Update
vbatFilterIsInitialised = true;
}
vbatSample = biquadFilterApply(&vbatFilter, vbatSample);

View file

@ -27,12 +27,14 @@
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/system.h"
#include "drivers/accgyro.h"
#include "sensors/sensors.h"
#include "io/beeper.h"
#include "io/statusindicator.h"
#include "sensors/boardalignment.h"
#include "sensors/sensors.h"
#include "sensors/boardalignment.h"
#include "sensors/gyro.h"
gyro_t gyro; // gyro access functions
@ -43,21 +45,27 @@ float gyroADCf[XYZ_AXIS_COUNT];
static int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 };
static const gyroConfig_t *gyroConfig;
static biquadFilter_t gyroFilter[XYZ_AXIS_COUNT];
static biquadFilter_t gyroFilterLPF[XYZ_AXIS_COUNT];
static biquadFilter_t gyroFilterNotch[XYZ_AXIS_COUNT];
static uint16_t gyroSoftNotchHz;
static uint8_t gyroSoftNotchQ;
static uint8_t gyroSoftLpfHz;
static uint16_t calibratingG = 0;
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz)
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz, uint16_t gyro_soft_notch_hz, uint8_t gyro_soft_notch_q)
{
gyroConfig = gyroConfigToUse;
gyroSoftLpfHz = gyro_soft_lpf_hz;
gyroSoftNotchHz = gyro_soft_notch_hz;
gyroSoftNotchQ = gyro_soft_notch_q;
}
void gyroInit(void)
{
if (gyroSoftLpfHz && gyro.targetLooptime) { // Initialisation needs to happen once samplingrate is known
for (int axis = 0; axis < 3; axis++) {
biquadFilterInit(&gyroFilter[axis], gyroSoftLpfHz, gyro.targetLooptime);
biquadFilterInit(&gyroFilterNotch[axis], gyroSoftNotchHz, gyro.targetLooptime, ((float) gyroSoftNotchQ) / 10, FILTER_NOTCH);
biquadFilterInitLPF(&gyroFilterLPF[axis], gyroSoftLpfHz, gyro.targetLooptime);
}
}
}
@ -157,7 +165,17 @@ void gyroUpdate(void)
if (gyroSoftLpfHz) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
gyroADCf[axis] = biquadFilterApply(&gyroFilter[axis], (float)gyroADC[axis]);
float sample = (float) gyroADC[axis];
if (gyroSoftNotchHz) {
sample = biquadFilterApply(&gyroFilterNotch[axis], sample);
}
if (debugMode == DEBUG_NOTCH && axis < 2){
debug[axis*2 + 0] = gyroADC[axis];
debug[axis*2 + 1] = lrintf(sample);
}
gyroADCf[axis] = biquadFilterApply(&gyroFilterLPF[axis], sample);;
gyroADC[axis] = lrintf(gyroADCf[axis]);
}
} else {

View file

@ -40,7 +40,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.
} gyroConfig_t;
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_lpf_hz);
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz, uint16_t gyro_soft_notch_hz, uint8_t gyro_soft_notch_q);
void gyroSetCalibrationCycles(void);
void gyroInit(void);
void gyroUpdate(void);

View file

@ -118,9 +118,15 @@ static bool fakeGyroReadTemp(int16_t *tempData)
return true;
}
static bool fakeGyroInitStatus(void) {
return true;
}
bool fakeGyroDetect(gyro_t *gyro)
{
gyro->init = fakeGyroInit;
gyro->intStatus = fakeGyroInitStatus;
gyro->read = fakeGyroRead;
gyro->temperature = fakeGyroReadTemp;
gyro->scale = 1.0f / 16.4f;
@ -143,6 +149,7 @@ bool fakeAccDetect(acc_t *acc)
{
acc->init = fakeAccInit;
acc->read = fakeAccRead;
acc->acc_1G = 512*8;
acc->revisionCode = 0;
return true;
}
@ -584,10 +591,14 @@ void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
}
}
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t accHardwareToUse, uint8_t magHardwareToUse, uint8_t baroHardwareToUse, int16_t magDeclinationFromConfig, uint8_t gyroLpf, uint8_t gyroSyncDenominator)
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig,
uint8_t accHardwareToUse,
uint8_t magHardwareToUse,
uint8_t baroHardwareToUse,
int16_t magDeclinationFromConfig,
uint8_t gyroLpf,
uint8_t gyroSyncDenominator)
{
int16_t deg, min;
memset(&acc, 0, sizeof(acc));
memset(&gyro, 0, sizeof(gyro));
@ -605,7 +616,6 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t a
detectAcc(accHardwareToUse);
detectBaro(baroHardwareToUse);
// Now time to init things, acc first
if (sensors(SENSOR_ACC)) {
acc.acc_1G = 256; // set default
@ -623,9 +633,8 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t a
// FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c
if (sensors(SENSOR_MAG)) {
// calculate magnetic declination
deg = magDeclinationFromConfig / 100;
min = magDeclinationFromConfig % 100;
const int16_t deg = magDeclinationFromConfig / 100;
const int16_t min = magDeclinationFromConfig % 100;
magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units
} else {
magneticDeclination = 0.0f; // TODO investigate if this is actually needed if there is no mag sensor or if the value stored in the config should be used.

View file

@ -24,10 +24,8 @@
#define LED0 PB5 // Blue LED - PB5
#define BEEPER PA0
#define USABLE_TIMER_CHANNEL_COUNT 9
// MPU6050 interrupts
@ -44,7 +42,6 @@
#define GYRO_MPU6050_ALIGN CW180_DEG
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW180_DEG
#define USE_GYRO_SPI_MPU6000
@ -52,7 +49,6 @@
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define MPU6000_CS_GPIO GPIOB
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_INSTANCE SPI2
@ -74,7 +70,6 @@
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART3_TX_PIN PB10 //(AF7)
#define UART3_RX_PIN PB11 //(AF7)

View file

@ -26,14 +26,14 @@
#define HW_PIN PB2
// LED's V1
#define LED0 PB4 // LED - PB4
#define LED1 PB5 // LED - PB5
#define LED0 PB4
#define LED1 PB5
// LED's V2
#define LED0_A PB8 // LED - PB8
#define LED1_A PB9 // LED - PB9
#define LED0_A PB8
#define LED1_A PB9
#define BEEPER PA5 // LED - PA5
#define BEEPER PA5
#define USABLE_TIMER_CHANNEL_COUNT 11
@ -65,7 +65,6 @@
// option to use MPU9150 or MPU9250 integrated AK89xx Mag
#define MAG
#define USE_MAG_AK8963
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
#define USE_VCP
@ -74,14 +73,14 @@
#define USE_UART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6 // PB6
#define UART1_RX_PIN PB7 // PB7
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PA2 // PA2
#define UART2_RX_PIN PA3 // PA3
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
@ -130,6 +129,5 @@
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) )

View file

@ -121,9 +121,7 @@
#define SERIAL_PORT_COUNT 4
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13

View file

@ -25,15 +25,15 @@
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_EXTI
#define INVERTER PB15
#define INVERTER_USART USART6
#define LED0 PB6
#define LED1 PB5
#define LED2 PB4
#define BEEPER PB7
#define BEEPER_INVERTED
#define LED0 PB6
#define LED1 PB5
#define LED2 PB4
#define INVERTER PB15
#define INVERTER_USART USART6
#define MPU6500_CS_PIN PC4
#define MPU6500_SPI_INSTANCE SPI1
@ -98,7 +98,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11

View file

@ -17,13 +17,13 @@
#define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D
#define LED0 PB3 // PB3 (LED)
#define LED0 PB3
#define INVERTER PB2 // PB2 (BOOT1) used as inverter select GPIO
#define INVERTER_USART USART1
#define BEEPER PB15 // PB15 (Beeper)
#define BEEPER_OPT PB2 // PB15 (Beeper)
#define BEEPER PB15
#define BEEPER_OPT PB2
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
@ -117,6 +117,7 @@
#undef GPS
#undef BARO
#undef MAG
#ifdef CC3D_OPBL
#define SKIP_CLI_COMMAND_HELP

View file

@ -81,7 +81,6 @@
#define ACC
#define USE_ACC_MPU6050
#define USE_ACC_LSM303DLHC
#define ACC_MPU6050_ALIGN CW0_DEG
#define BARO
@ -89,7 +88,6 @@
#define MAG
#define USE_MAG_AK8975
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
#define USE_VCP
@ -115,6 +113,5 @@
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)|BIT(9)|BIT(10))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))

View file

@ -20,9 +20,9 @@
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
#define USE_HARDWARE_REVISION_DETECTION
#define LED0 PC14 // PC14 (LED)
#define LED1 PC13 // PC13 (LED)
#define LED2 PC15 // PC15 (LED)
#define LED0 PC14
#define LED1 PC13
#define LED2 PC15
#define ACC
#define USE_ACC_MPU6050

View file

@ -23,10 +23,8 @@
// tqfp48 pin 34
#define LED0 PA13
// tqfp48 pin 37
#define LED1 PA14
// tqfp48 pin 38
#define LED2 PA15
@ -109,8 +107,8 @@
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5

View file

@ -19,8 +19,8 @@
#define TARGET_BOARD_IDENTIFIER "EUF1"
#define LED0 PB3 // PB3 (LED)
#define LED1 PB4 // PB4 (LED)
#define LED0 PB3
#define LED1 PB4
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_USART USART2
@ -112,6 +112,5 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -25,6 +25,7 @@
#define LED0 PE3 // Blue LED
#define LED1 PE2 // Red LED
#define LED2 PE1 // Blue LED
#define BEEPER PE5
#define INVERTER PD3
@ -103,11 +104,9 @@
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 6 //VCP, UART1, UART2, UART3, UART4, UART5, UART6
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
@ -127,15 +126,14 @@
#define SPI3_MOSI_PIN PB5
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define USE_I2C_PULLUP
#define I2C2_SCL PB10
#define I2C2_SDA PB11
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define VBAT_ADC_PIN PC3
#define CURRENT_METER_ADC_PIN PC2
#define RSSI_ADC_PIN PC1

View file

@ -36,11 +36,9 @@
#define ENSURE_MPU_DATA_READY_IS_LOW
#define GYRO
#define ACC
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1
@ -53,6 +51,7 @@
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW90_DEG
#define ACC
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW90_DEG
@ -113,11 +112,11 @@
#define USE_SOFTSERIAL1
#define SERIAL_PORT_COUNT 5
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14 // PA14
#define UART2_RX_PIN PA15 // PA15
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
@ -132,8 +131,8 @@
#define I2C1_SCL_PIN PB8
#define I2C1_SDA_PIN PB9
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PA0
#define RSSI_ADC_PIN PA1

View file

@ -24,6 +24,7 @@
#define LED0 PB5
#define LED1 PB4
#define BEEPER PA8
#define BEEPER_INVERTED

View file

@ -49,14 +49,14 @@
#define USE_UART3
#define SERIAL_PORT_COUNT 3
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14 // PA14 / SWCLK
#define UART2_RX_PIN PA15 // PA15
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
@ -67,8 +67,8 @@
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
@ -105,6 +105,5 @@
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))

View file

@ -24,6 +24,7 @@
#define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED | SERIAL_BIDIR)
#define LED0 PB1
#define BEEPER PB13
#define BEEPER_INVERTED
@ -42,16 +43,14 @@
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW180_DEG
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4

View file

@ -68,11 +68,11 @@
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6 // PB6
#define UART1_RX_PIN PB7 // PB7
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PB3 // PB3
#define UART2_RX_PIN PB4 // PB4
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
@ -96,8 +96,8 @@
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA5
//#define CURRENT_METER_ADC_PIN PA5

View file

@ -22,10 +22,10 @@
#define BOARD_HAS_VOLTAGE_DIVIDER
#define LED0 PB3 // PB3 (LED)
#define LED1 PB4 // PB4 (LED)
#define LED0 PB3
#define LED1 PB4
#define BEEPER PA12 // PA12 (Beeper)
#define BEEPER PA12
#ifdef AFROMINI
#define BEEPER_INVERTED
#endif
@ -62,9 +62,7 @@
#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define EXTI_CALLBACK_HANDLER_COUNT 3 // MPU data ready, MAG data ready, BMP085 EOC
@ -82,7 +80,6 @@
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU3050_ALIGN CW0_DEG
#define GYRO_MPU6050_ALIGN CW0_DEG
#define GYRO_MPU6500_ALIGN CW0_DEG
@ -108,7 +105,6 @@
#define MAG
#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW180_DEG
#define SONAR

View file

@ -91,5 +91,4 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -65,7 +65,6 @@
#define USB_IO
#define USB_CABLE_DETECTION
#define USB_DETECT_PIN PB5
#define USE_VCP
@ -74,11 +73,11 @@
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14 // PA14 / SWCLK
#define UART2_RX_PIN PA15 // PA15
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
@ -169,6 +168,7 @@
#define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_ONESHOT125)

View file

@ -101,5 +101,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5 }, // S6_OUT
};

View file

@ -37,10 +37,10 @@
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO
#define ACC
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
@ -54,11 +54,11 @@
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6 // PB6
#define UART1_RX_PIN PB7 // PB7
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PB3 // PB3
#define UART2_RX_PIN PB4 // PB4
#define UART2_TX_PIN PB3
#define UART2_RX_PIN PB4
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
@ -73,8 +73,8 @@
#define SERIAL_RX
#define USE_SERVOS
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define CURRENT_METER_ADC_PIN PA2
#define VBAT_ADC_PIN PA5
@ -137,3 +137,4 @@
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View file

@ -19,8 +19,8 @@
#define TARGET_BOARD_IDENTIFIER "103R"
#define LED0 PB3 // PB3 (LED)
#define LED1 PB4 // PB4 (LED)
#define LED0 PB3
#define LED1 PB4
#define LED2 PD2 // PD2 (LED) - Labelled LED4
#define BEEPER PA12 // PA12 (Beeper)
@ -123,7 +123,5 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -121,4 +121,4 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9))
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) )

View file

@ -27,7 +27,9 @@
#define LED0 PC14
#define LED1 PC13
#define BEEPER PC13
#define INVERTER PC15
#define INVERTER_USART USART2 //Sbus on USART 2 of nano.
@ -96,6 +98,5 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) )

View file

@ -62,8 +62,8 @@
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 5
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14 // PA14 / SWCLK
#define UART2_RX_PIN PA15 // PA15
@ -88,8 +88,8 @@
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
@ -119,5 +119,5 @@
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))

View file

@ -61,8 +61,8 @@
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA2 // PA14 / SWCLK
#define UART2_RX_PIN PA3 // PA15
@ -124,19 +124,20 @@
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PA0
//#define USE_QUAD_MIXER_ONLY
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define OSD
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define USE_SERVOS
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL | FEATURE_OSD | FEATURE_VTX)

View file

@ -38,12 +38,10 @@
// MPU 9150 INT connected to PA15, pulled up to VCC by 10K Resistor, contains MPU6050 and AK8975 in single component.
#define GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW270_DEG
#define ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW270_DEG
#define BARO
@ -61,11 +59,11 @@
#define USE_UART3 // Servo out - 10/RX (PB11) 11/TX (PB10)
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PB6 // PB6
#define UART1_RX_PIN PB7 // PB7
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PA2 // PA2 - Clashes with PWM6 input.
#define UART2_RX_PIN PA3 // PA3
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
@ -129,7 +127,5 @@
#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(6)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(12)|BIT(13))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View file

@ -72,11 +72,11 @@
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 5
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14 // PA14 / SWCLK
#define UART2_RX_PIN PA15 // PA15
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
@ -97,8 +97,8 @@
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
@ -133,4 +133,3 @@
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )

View file

@ -70,11 +70,11 @@
#define USE_UART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14 // PA14 / SWCLK
#define UART2_RX_PIN PA15 // PA15
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
@ -117,9 +117,8 @@
#define MPU6500_CS_PIN PB9
#define MPU6500_SPI_INSTANCE SPI1
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
@ -164,6 +163,5 @@
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15))

View file

@ -41,17 +41,15 @@
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
#define GYRO
//#define USE_FAKE_GYRO
#define USE_GYRO_MPU6500
#define GYRO_MPU6500_ALIGN CW180_DEG
#define ACC
//#define USE_FAKE_ACC
#define USE_ACC_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG
#define GYRO_MPU6500_ALIGN CW180_DEG
#define BARO
#define USE_BARO_BMP280
@ -60,7 +58,6 @@
#define USE_MPU9250_MAG // Enables bypass configuration
#define USE_MAG_AK8975
#define USE_MAG_HMC5883 // External
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
#define SONAR
@ -79,11 +76,11 @@
#define USE_SOFTSERIAL1
#define SERIAL_PORT_COUNT 5
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14 // PA14 / SWCLK
#define UART2_RX_PIN PA15 // PA15
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
@ -124,10 +121,8 @@
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
@ -141,7 +136,6 @@
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
#define TRANSPONDER
#define TRANSPONDER_GPIO GPIOA
#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
@ -158,6 +152,7 @@
#define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES FEATURE_BLACKBOX
@ -182,3 +177,4 @@
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))

View file

@ -153,7 +153,6 @@
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
#define LED_STRIP
#define LED_STRIP_TIMER TIM16
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -28,8 +28,6 @@
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
@ -62,11 +60,11 @@
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 5
#define UART1_TX_PIN PA9 // PA9
#define UART1_RX_PIN PA10 // PA10
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA2 // PA14 / SWCLK
#define UART2_RX_PIN PA3 // PA15
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
@ -100,8 +98,8 @@
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
@ -136,4 +134,3 @@
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )

View file

@ -36,17 +36,15 @@
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
#define GYRO
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW180_DEG
#define ACC
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG
#define GYRO_MPU6500_ALIGN CW180_DEG
#define BARO
#define USE_BARO_BMP280
@ -58,7 +56,7 @@
#define UART2_TX_PIN PA14 // PA14 / SWCLK
#define UART2_RX_PIN PA15 // PA15
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
@ -84,8 +82,8 @@
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5