Merge pull request #681 from betaflight/development

Development into master
This commit is contained in:
borisbstyle 2016-07-05 22:35:22 +02:00 committed by GitHub
commit 1c67a9414b
178 changed files with 3114 additions and 2126 deletions

View File

@ -600,6 +600,7 @@ LDFLAGS = -lm \
-Wl,-gc-sections,-Map,$(TARGET_MAP) \
-Wl,-L$(LINKER_DIR) \
-Wl,--cref \
-Wl,--no-wchar-size-warning \
-T$(LD_SCRIPT)
###############################################################################
@ -664,27 +665,39 @@ all: $(VALID_TARGETS)
$(VALID_TARGETS):
echo "" && \
echo "Building $@" && \
$(MAKE) -j binary hex TARGET=$@ && \
$(MAKE) binary hex TARGET=$@ && \
echo "Building $@ succeeded."
## clean : clean up all temporary / machine-generated files
CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
## clean : clean up temporary / machine-generated files
clean:
echo "Cleaning $(TARGET)"
rm -f $(CLEAN_ARTIFACTS)
rm -rf $(OBJECT_DIR)/$(TARGET)
echo "Cleaning $(TARGET) succeeded."
## clean_test : clean up all temporary / machine-generated files (tests)
## clean_test : clean up temporary / machine-generated files (tests)
clean_test:
cd src/test && $(MAKE) clean || true
## clean_all_targets : clean all valid target platforms
clean_all:
for clean_target in $(VALID_TARGETS); do \
echo "" && \
echo "Cleaning $$clean_target" && \
$(MAKE) -j TARGET=$$clean_target clean || \
break; \
echo "Cleaning $$clean_target succeeded."; \
done
## clean_<TARGET> : clean up one specific target
$(CLEAN_TARGETS) :
$(MAKE) -j TARGET=$(subst clean_,,$@) clean
## <TARGET>_clean : clean up one specific target (alias for above)
$(TARGETS_CLEAN) :
$(MAKE) -j TARGET=$(subst _clean,,$@) clean
## clean_all : clean all valid targets
clean_all:$(CLEAN_TARGETS)
## all_clean : clean all valid targets (alias for above)
all_clean:$(TARGETS_CLEAN)
flash_$(TARGET): $(TARGET_HEX)
stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
@ -700,8 +713,11 @@ st-flash_$(TARGET): $(TARGET_BIN)
## st-flash : flash firmware (.bin) onto flight controller
st-flash: st-flash_$(TARGET)
binary: $(TARGET_BIN)
hex: $(TARGET_HEX)
binary:
$(MAKE) -j $(TARGET_BIN)
hex:
$(MAKE) -j $(TARGET_HEX)
unbrick_$(TARGET): $(TARGET_HEX)
stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon

View File

@ -1,6 +1,6 @@
# Betaflight
![Betaflight](https://dl.dropboxusercontent.com/u/31537757/betaflight%20logo.jpg)
![Betaflight](https://camo.githubusercontent.com/8178215d6cb90842dc95c9d437b1bdf09b2d57a7/687474703a2f2f7374617469632e726367726f7570732e6e65742f666f72756d732f6174746163686d656e74732f362f312f302f332f372f362f61393038383930302d3232382d62665f6c6f676f2e6a7067)
Clean-code version of baseflight flight-controller - flight controllers are used to fly multi-rotor craft and fixed wing craft.

View File

@ -20,7 +20,10 @@ targets=("PUBLISHMETA=True" \
"TARGET=ALIENFLIGHTF3" \
"TARGET=DOGE" \
"TARGET=SINGULARITY" \
"TARGET=SIRINFPV")
"TARGET=SIRINFPV" \
"TARGET=X_RACERSPI")
#fake a travis build environment
export TRAVIS_BUILD_NUMBER=$(date +%s)

View File

@ -325,9 +325,6 @@ extern uint32_t currentTime;
//From rx.c:
extern uint16_t rssi;
//From gyro.c
extern uint32_t targetLooptime;
//From rc_controls.c
extern uint32_t rcModeActivationMask;
@ -1169,7 +1166,7 @@ static bool blackboxWriteSysinfo()
}
);
BLACKBOX_PRINT_HEADER_LINE("looptime:%d", targetLooptime);
BLACKBOX_PRINT_HEADER_LINE("looptime:%d", gyro.targetLooptime);
BLACKBOX_PRINT_HEADER_LINE("rcRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcRate8);
BLACKBOX_PRINT_HEADER_LINE("rcExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcExpo8);
BLACKBOX_PRINT_HEADER_LINE("rcYawRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawRate8);

View File

@ -22,7 +22,6 @@
#include "drivers/accgyro.h"
#include "drivers/light_led.h"
#include "drivers/sound_beeper.h"
#include "drivers/gyro_sync.h"
#include "sensors/sensors.h"
#include "sensors/boardalignment.h"

View File

@ -17,10 +17,8 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <math.h>
#include "common/axis.h"
#include "common/filter.h"
#include "common/maths.h"
@ -30,63 +28,70 @@
#define BIQUAD_BANDWIDTH 1.9f /* bandwidth in octaves */
#define BIQUAD_Q 1.0f / sqrtf(2.0f) /* quality factor - butterworth*/
// PT1 Low Pass filter (when no dT specified it will be calculated from the cycleTime)
float filterApplyPt1(float input, filterStatePt1_t *filter, float f_cut, float dT) {
// PT1 Low Pass filter
void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT)
{
filter->RC = 1.0f / ( 2.0f * M_PI_FLOAT * f_cut );
filter->dT = dT;
}
float pt1FilterApply(pt1Filter_t *filter, float input)
{
filter->state = filter->state + filter->dT / (filter->RC + filter->dT) * (input - filter->state);
return filter->state;
}
float pt1FilterApply4(pt1Filter_t *filter, float input, uint8_t f_cut, float dT)
{
// Pre calculate and store RC
if (!filter->RC) {
filter->RC = 1.0f / ( 2.0f * M_PI_FLOAT * f_cut );
filter->dT = dT;
}
filter->state = filter->state + dT / (filter->RC + dT) * (input - filter->state);
filter->state = filter->state + filter->dT / (filter->RC + filter->dT) * (input - filter->state);
return filter->state;
}
/* sets up a biquad Filter */
void BiQuadNewLpf(float filterCutFreq, biquad_t *newState, uint32_t refreshRate)
void biquadFilterInit(biquadFilter_t *filter, float filterCutFreq, uint32_t refreshRate)
{
float sampleRate;
const float sampleRate = 1 / ((float)refreshRate * 0.000001f);
sampleRate = 1 / ((float)refreshRate * 0.000001f);
float omega, sn, cs, alpha;
float a0, a1, a2, b0, b1, b2;
/* setup variables */
omega = 2 * M_PI_FLOAT * filterCutFreq / sampleRate;
sn = sinf(omega);
cs = cosf(omega);
// setup variables
const float omega = 2 * M_PI_FLOAT * filterCutFreq / 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);
alpha = sn / (2 * BIQUAD_Q);
const float alpha = sn / (2 * BIQUAD_Q);
b0 = (1 - cs) / 2;
b1 = 1 - cs;
b2 = (1 - cs) / 2;
a0 = 1 + alpha;
a1 = -2 * cs;
a2 = 1 - alpha;
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;
/* precompute the coefficients */
newState->b0 = b0 / a0;
newState->b1 = b1 / a0;
newState->b2 = b2 / a0;
newState->a1 = a1 / a0;
newState->a2 = a2 / a0;
// precompute the coefficients
filter->b0 = b0 / a0;
filter->b1 = b1 / a0;
filter->b2 = b2 / a0;
filter->a1 = a1 / a0;
filter->a2 = a2 / a0;
/* zero initial samples */
newState->d1 = newState->d2 = 1;
// zero initial samples
filter->d1 = filter->d2 = 0;
}
/* Computes a biquad_t filter on a sample */
float applyBiQuadFilter(float sample, biquad_t *state) //direct form 2 transposed
float biquadFilterApply(biquadFilter_t *filter, float input)
{
float result;
result = state->b0 * sample + state->d1;
state->d1 = state->b1 * sample - state->a1 * result + state->d2;
state->d2 = state->b2 * sample - state->a2 * result;
const float result = filter->b0 * input + filter->d1;
filter->d1 = filter->b1 * input - filter->a1 * result + filter->d2;
filter->d2 = filter->b2 * input - filter->a2 * result;
return result;
}

View File

@ -17,20 +17,26 @@
#define DELTA_MAX_SAMPLES 12
typedef struct filterStatePt1_s {
typedef struct pt1Filter_s {
float state;
float RC;
float constdT;
} filterStatePt1_t;
float dT;
} pt1Filter_t;
/* this holds the data required to update samples thru a filter */
typedef struct biquad_s {
typedef struct biquadFilter_s {
float b0, b1, b2, a1, a2;
float d1, d2;
} biquad_t;
} biquadFilter_t;
void biquadFilterInit(biquadFilter_t *filter, float filterCutFreq, uint32_t refreshRate);
float biquadFilterApply(biquadFilter_t *filter, float input);
void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT);
float pt1FilterApply(pt1Filter_t *filter, float input);
float pt1FilterApply4(pt1Filter_t *filter, float input, uint8_t f_cut, float dT);
float applyBiQuadFilter(float sample, biquad_t *state);
float filterApplyPt1(float input, filterStatePt1_t *filter, float f_cut, float dt);
int32_t filterApplyAverage(int32_t input, uint8_t averageCount, int32_t averageState[DELTA_MAX_SAMPLES]);
float filterApplyAveragef(float input, uint8_t averageCount, float averageState[DELTA_MAX_SAMPLES]);
void BiQuadNewLpf(float filterCutFreq, biquad_t *newState, uint32_t refreshRate);

View File

@ -38,7 +38,6 @@
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/gyro_sync.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
@ -90,6 +89,7 @@
#endif
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
void targetConfiguration(void);
#if !defined(FLASH_SIZE)
#error "Flash size not defined for target. (specify in KB)"
@ -269,8 +269,13 @@ void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig)
{
#ifdef BRUSHED_MOTORS
escAndServoConfig->minthrottle = 1000;
escAndServoConfig->maxthrottle = 2000;
#else
escAndServoConfig->minthrottle = 1150;
escAndServoConfig->maxthrottle = 1850;
#endif
escAndServoConfig->mincommand = 1000;
escAndServoConfig->servoCenterPulse = 1500;
escAndServoConfig->escDesyncProtection = 0;
@ -416,8 +421,6 @@ uint16_t getCurrentMinthrottle(void)
// Default settings
static void resetConf(void)
{
int i;
// Clear all configuration
memset(&masterConfig, 0, sizeof(master_t));
setProfile(0);
@ -478,7 +481,11 @@ static void resetConf(void)
resetTelemetryConfig(&masterConfig.telemetryConfig);
#ifdef SERIALRX_PROVIDER
masterConfig.rxConfig.serialrx_provider = SERIALRX_PROVIDER;
#else
masterConfig.rxConfig.serialrx_provider = 0;
#endif
masterConfig.rxConfig.sbus_inversion = 1;
masterConfig.rxConfig.spektrum_sat_bind = 0;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
@ -488,7 +495,7 @@ static void resetConf(void)
masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i];
channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc);
@ -550,8 +557,7 @@ static void resetConf(void)
resetPidProfile(&currentProfile->pidProfile);
uint8_t rI;
for (rI = 0; rI<MAX_RATEPROFILES; rI++) {
for (int rI = 0; rI<MAX_RATEPROFILES; rI++) {
resetControlRateConfig(&masterConfig.profile[0].controlRateProfile[rI]);
}
resetRollAndPitchTrims(&masterConfig.accelerometerTrims);
@ -582,7 +588,7 @@ static void resetConf(void)
#ifdef USE_SERVOS
// servos
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
masterConfig.servoConf[i].min = DEFAULT_SERVO_MIN;
masterConfig.servoConf[i].max = DEFAULT_SERVO_MAX;
masterConfig.servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
@ -601,8 +607,9 @@ static void resetConf(void)
#endif
// custom mixer. clear by defaults.
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
masterConfig.customMotorMixer[i].throttle = 0.0f;
}
#ifdef LED_STRIP
applyDefaultColors(masterConfig.colors, CONFIGURABLE_COLOR_COUNT);
@ -640,61 +647,18 @@ static void resetConf(void)
#endif // BLACKBOX
// alternative defaults settings for COLIBRI RACE targets
#if defined(COLIBRI_RACE)
masterConfig.escAndServoConfig.minthrottle = 1025;
masterConfig.escAndServoConfig.maxthrottle = 1980;
masterConfig.batteryConfig.vbatmaxcellvoltage = 45;
masterConfig.batteryConfig.vbatmincellvoltage = 30;
#ifdef SERIALRX_UART
if (featureConfigured(FEATURE_RX_SERIAL)) {
masterConfig.serialConfig.portConfigs[SERIALRX_UART].functionMask = FUNCTION_RX_SERIAL;
}
#endif
#if defined(TARGET_CONFIG)
targetConfiguration(&masterConfig);
#endif
#if defined(ALIENFLIGHT)
featureClear(FEATURE_ONESHOT125);
#ifdef ALIENFLIGHTF1
masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
#else
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
#endif
#ifdef ALIENFLIGHTF3
masterConfig.batteryConfig.vbatscale = 20;
masterConfig.mag_hardware = MAG_NONE; // disabled by default
#endif
masterConfig.rxConfig.serialrx_provider = SERIALRX_SPEKTRUM2048;
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.escAndServoConfig.minthrottle = 1000;
masterConfig.escAndServoConfig.maxthrottle = 2000;
masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
currentControlRateProfile->rates[FD_PITCH] = 40;
currentControlRateProfile->rates[FD_ROLL] = 40;
currentControlRateProfile->rates[FD_YAW] = 40;
parseRcChannels("TAER1234", &masterConfig.rxConfig);
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
#endif
#if defined(SINGULARITY)
// alternative defaults settings for SINGULARITY target
masterConfig.batteryConfig.vbatscale = 77;
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
targetConfiguration();
#endif
// copy first profile into remaining profile
for (i = 1; i < MAX_PROFILE_COUNT; i++) {
for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));
}
@ -751,7 +715,7 @@ void activateConfig(void)
&currentProfile->pidProfile
);
useGyroConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz);
gyroUseConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz);
#ifdef TELEMETRY
telemetryUseConfig(&masterConfig.telemetryConfig);
@ -806,7 +770,7 @@ void activateConfig(void)
void validateAndFixConfig(void)
{
if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP))) {
featureSet(FEATURE_RX_PARALLEL_PWM); // Consider changing the default to PPM
featureSet(DEFAULT_RX_FEATURE);
}
if (featureConfigured(FEATURE_RX_PPM)) {
@ -848,10 +812,10 @@ void validateAndFixConfig(void)
if (featureConfigured(FEATURE_SOFTSERIAL) && (
0
#ifdef USE_SOFTSERIAL1
|| (LED_STRIP_TIMER == SOFTSERIAL_1_TIMER)
|| (WS2811_TIMER == SOFTSERIAL_1_TIMER)
#endif
#ifdef USE_SOFTSERIAL2
|| (LED_STRIP_TIMER == SOFTSERIAL_2_TIMER)
|| (WS2811_TIMER == SOFTSERIAL_2_TIMER)
#endif
)) {
// led strip needs the same timer as softserial
@ -901,15 +865,11 @@ void validateAndFixConfig(void)
#if defined(COLIBRI_RACE)
masterConfig.serialConfig.portConfigs[0].functionMask = FUNCTION_MSP;
if(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) {
if (featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) {
featureClear(FEATURE_RX_PARALLEL_PWM);
featureClear(FEATURE_RX_MSP);
featureSet(FEATURE_RX_PPM);
}
if(featureConfigured(FEATURE_RX_SERIAL)) {
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
//masterConfig.rxConfig.serialrx_provider = SERIALRX_SBUS;
}
#endif
useRxConfig(&masterConfig.rxConfig);

View File

@ -27,6 +27,7 @@ typedef struct gyro_s {
sensorReadFuncPtr temperature; // read temperature if available
sensorInterruptFuncPtr intStatus;
float scale; // scalefactor
uint32_t targetLooptime;
} gyro_t;
typedef struct acc_s {

View File

@ -26,7 +26,7 @@
#include "common/axis.h"
#include "system.h"
#include "gpio.h"
#include "io.h"
#include "bus_i2c.h"
#include "sensor.h"

View File

@ -22,8 +22,7 @@
*/
/* LSM303DLHC ACC struct */
typedef struct
{
typedef struct {
uint8_t Power_Mode; /* Power-down/Normal Mode */
uint8_t AccOutput_DataRate; /* OUT data rate */
uint8_t Axes_Enable; /* Axes enable */
@ -31,25 +30,23 @@ typedef struct
uint8_t BlockData_Update; /* Block Data Update */
uint8_t Endianness; /* Endian Data selection */
uint8_t AccFull_Scale; /* Full Scale selection */
}LSM303DLHCAcc_InitTypeDef;
} LSM303DLHCAcc_InitTypeDef;
/* LSM303DLHC Acc High Pass Filter struct */
typedef struct
{
typedef struct {
uint8_t HighPassFilter_Mode_Selection; /* Internal filter mode */
uint8_t HighPassFilter_CutOff_Frequency; /* High pass filter cut-off frequency */
uint8_t HighPassFilter_AOI1; /* HPF_enabling/disabling for AOI function on interrupt 1 */
uint8_t HighPassFilter_AOI2; /* HPF_enabling/disabling for AOI function on interrupt 2 */
}LSM303DLHCAcc_FilterConfigTypeDef;
} LSM303DLHCAcc_FilterConfigTypeDef;
/* LSM303DLHC Mag struct */
typedef struct
{
typedef struct {
uint8_t Temperature_Sensor; /* Temperature sensor enable/disable */
uint8_t MagOutput_DataRate; /* OUT data rate */
uint8_t Working_Mode; /* operating mode */
uint8_t MagFull_Scale; /* Full Scale selection */
}LSM303DLHCMag_InitTypeDef;
} LSM303DLHCMag_InitTypeDef;
/**
* @}
*/
@ -78,43 +75,11 @@ typedef struct
* @brief LSM303DLHC I2C Interface pins
*/
#define LSM303DLHC_I2C I2C1
#define LSM303DLHC_I2C_CLK RCC_APB1Periph_I2C1
#define LSM303DLHC_I2C_SCK_PIN GPIO_Pin_6 /* PB.06 */
#define LSM303DLHC_I2C_SCK_GPIO_PORT GPIOB /* GPIOB */
#define LSM303DLHC_I2C_SCK_GPIO_CLK RCC_AHBPeriph_GPIOB
#define LSM303DLHC_I2C_SCK_SOURCE GPIO_PinSource6
#define LSM303DLHC_I2C_SCK_AF GPIO_AF_4
#define LSM303DLHC_I2C_SDA_PIN GPIO_Pin_7 /* PB.7 */
#define LSM303DLHC_I2C_SDA_GPIO_PORT GPIOB /* GPIOB */
#define LSM303DLHC_I2C_SDA_GPIO_CLK RCC_AHBPeriph_GPIOB
#define LSM303DLHC_I2C_SDA_SOURCE GPIO_PinSource7
#define LSM303DLHC_I2C_SDA_AF GPIO_AF_4
#define LSM303DLHC_DRDY_PIN GPIO_Pin_2 /* PE.02 */
#define LSM303DLHC_DRDY_GPIO_PORT GPIOE /* GPIOE */
#define LSM303DLHC_DRDY_GPIO_CLK RCC_AHBPeriph_GPIOE
#define LSM303DLHC_DRDY_EXTI_LINE EXTI_Line2
#define LSM303DLHC_DRDY_EXTI_PORT_SOURCE EXTI_PortSourceGPIOE
#define LSM303DLHC_DRDY_EXTI_PIN_SOURCE EXTI_PinSource2
#define LSM303DLHC_DRDY_EXTI_IRQn EXTI2_TS_IRQn
#define LSM303DLHC_I2C_INT1_PIN GPIO_Pin_4 /* PE.04 */
#define LSM303DLHC_I2C_INT1_GPIO_PORT GPIOE /* GPIOE */
#define LSM303DLHC_I2C_INT1_GPIO_CLK RCC_AHBPeriph_GPIOE
#define LSM303DLHC_I2C_INT1_EXTI_LINE EXTI_Line4
#define LSM303DLHC_I2C_INT1_EXTI_PORT_SOURCE EXTI_PortSourceGPIOE
#define LSM303DLHC_I2C_INT1_EXTI_PIN_SOURCE EXTI_PinSource4
#define LSM303DLHC_I2C_INT1_EXTI_IRQn EXTI4_IRQn
#define LSM303DLHC_I2C_INT2_PIN GPIO_Pin_5 /* PE.05 */
#define LSM303DLHC_I2C_INT2_GPIO_PORT GPIOE /* GPIOE */
#define LSM303DLHC_I2C_INT2_GPIO_CLK RCC_AHBPeriph_GPIOE
#define LSM303DLHC_I2C_INT2_EXTI_LINE EXTI_Line5
#define LSM303DLHC_I2C_INT2_EXTI_PORT_SOURCE EXTI_PortSourceGPIOE
#define LSM303DLHC_I2C_INT2_EXTI_PIN_SOURCE EXTI_PinSource5ss
#define LSM303DLHC_I2C_INT2_EXTI_IRQn EXTI9_5_IRQn
#define LSM303DLHC_I2C_SCK_PIN PB6 /* PB.06 */
#define LSM303DLHC_I2C_SDA_PIN PB7 /* PB.7 */
#define LSM303DLHC_DRDY_PIN PE2 /* PE.02 */
#define LSM303DLHC_I2C_INT1_PIN PE4 /* PE.04 */
#define LSM303DLHC_I2C_INT2_PIN PE5 /* PE.05 */
/******************************************************************************/
/*************************** START REGISTER MAPPING **************************/

View File

@ -32,7 +32,6 @@
#include "gpio.h"
#include "exti.h"
#include "bus_i2c.h"
#include "gyro_sync.h"
#include "sensor.h"
#include "accgyro.h"
@ -300,11 +299,14 @@ bool mpuGyroRead(int16_t *gyroADC)
return true;
}
void checkMPUDataReady(bool *mpuDataReadyPtr) {
bool checkMPUDataReady(void)
{
bool ret;
if (mpuDataReady) {
*mpuDataReadyPtr = true;
ret = true;
mpuDataReady= false;
} else {
*mpuDataReadyPtr = false;
ret = false;
}
return ret;
}

View File

@ -17,6 +17,8 @@
#pragma once
#include "exti.h"
// MPU6050
#define MPU_RA_WHO_AM_I 0x75
#define MPU_RA_WHO_AM_I_LEGACY 0x00
@ -185,4 +187,4 @@ void mpuIntExtiInit(void);
bool mpuAccRead(int16_t *accData);
bool mpuGyroRead(int16_t *gyroADC);
mpuDetectionResult_t *detectMpu(const extiConfig_t *configToUse);
void checkMPUDataReady(bool *mpuDataReadyPtr);
bool checkMPUDataReady(void);

View File

@ -30,7 +30,6 @@
#include "accgyro.h"
#include "accgyro_mpu.h"
#include "accgyro_mpu3050.h"
#include "gyro_sync.h"
// MPU3050, Standard address 0x68
#define MPU3050_ADDRESS 0x68

View File

@ -1,4 +1,4 @@
/*
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
@ -38,8 +38,6 @@
#include "accgyro_mpu.h"
#include "accgyro_mpu6050.h"
extern uint8_t mpuLowPassFilter;
//#define DEBUG_MPU_DATA_READY_INTERRUPT
// MPU6050, Standard address 0x68

View File

@ -17,6 +17,8 @@
#pragma once
#include "io.h"
typedef enum {
ADC_BATTERY = 0,
ADC_RSSI = 1,
@ -28,6 +30,7 @@ typedef enum {
#define ADC_CHANNEL_COUNT (ADC_CHANNEL_MAX + 1)
typedef struct adc_config_s {
ioTag_t tag;
uint8_t adcChannel; // ADC1_INxx channel number
uint8_t dmaIndex; // index into DMA buffer in case of sparse channels
bool enabled;

View File

@ -91,45 +91,25 @@ void adcInit(drv_adc_config_t *init)
#ifdef VBAT_ADC_PIN
if (init->enableVBat) {
IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0));
adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN));
adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_BATTERY].enabled = true;
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_239Cycles5;
adcConfig[ADC_BATTERY].tag = IO_TAG(VBAT_ADC_PIN);
}
#endif
#ifdef RSSI_ADC_PIN
if (init->enableRSSI) {
IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0));
adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN));
adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_RSSI].enabled = true;
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_239Cycles5;
adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN);
}
#endif
#ifdef EXTERNAL1_ADC_PIN
if (init->enableExternal1) {
IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0));
adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN));
adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_EXTERNAL1].enabled = true;
adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_239Cycles5;
adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN);
}
#endif
#ifdef CURRENT_METER_ADC_PIN
if (init->enableCurrentMeter) {
IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0));
adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN));
adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_CURRENT].enabled = true;
adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_239Cycles5;
adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN);
}
#endif
@ -139,12 +119,22 @@ void adcInit(drv_adc_config_t *init)
adcDevice_t adc = adcHardware[device];
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag)
continue;
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AIN, 0));
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
adcConfig[i].dmaIndex = configuredAdcChannels++;
adcConfig[i].sampleTime = ADC_SampleTime_239Cycles5;
adcConfig[i].enabled = true;
}
RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI)
RCC_ClockCmd(adc.rccADC, ENABLE);
RCC_ClockCmd(adc.rccDMA, ENABLE);
// FIXME ADC driver assumes all the GPIO was already placed in 'AIN' mode
DMA_DeInit(adc.DMAy_Channelx);
DMA_InitTypeDef DMA_InitStructure;
DMA_StructInit(&DMA_InitStructure);

View File

@ -107,53 +107,25 @@ void adcInit(drv_adc_config_t *init)
#ifdef VBAT_ADC_PIN
if (init->enableVBat) {
IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN));
adcConfig[ADC_BATTERY].dmaIndex = adcChannelCount;
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_601Cycles5;
adcConfig[ADC_BATTERY].enabled = true;
adcChannelCount++;
adcConfig[ADC_BATTERY].tag = IO_TAG(VBAT_ADC_PIN);
}
#endif
#ifdef RSSI_ADC_PIN
if (init->enableRSSI) {
IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN));
adcConfig[ADC_RSSI].dmaIndex = adcChannelCount;
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_601Cycles5;
adcConfig[ADC_RSSI].enabled = true;
adcChannelCount++;
adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN);
}
#endif
#ifdef CURRENT_METER_ADC_GPIO
#ifdef CURRENT_METER_ADC_PIN
if (init->enableCurrentMeter) {
IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN));
adcConfig[ADC_CURRENT].dmaIndex = adcChannelCount;
adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_601Cycles5;
adcConfig[ADC_CURRENT].enabled = true;
adcChannelCount++;
adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN);
}
#endif
#ifdef EXTERNAL1_ADC_GPIO
#ifdef EXTERNAL1_ADC_PIN
if (init->enableExternal1) {
IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN));
adcConfig[ADC_EXTERNAL1].dmaIndex = adcChannelCount;
adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_601Cycles5;
adcConfig[ADC_EXTERNAL1].enabled = true;
adcChannelCount++;
adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN);
}
#endif
@ -163,6 +135,18 @@ void adcInit(drv_adc_config_t *init)
adcDevice_t adc = adcHardware[device];
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag)
continue;
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
adcConfig[i].dmaIndex = adcChannelCount++;
adcConfig[i].sampleTime = ADC_SampleTime_601Cycles5;
adcConfig[i].enabled = true;
}
RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
RCC_ClockCmd(adc.rccADC, ENABLE);
RCC_ClockCmd(adc.rccDMA, ENABLE);

View File

@ -100,45 +100,25 @@ void adcInit(drv_adc_config_t *init)
#ifdef VBAT_ADC_PIN
if (init->enableVBat) {
IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN)); //VBAT_ADC_CHANNEL;
adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_BATTERY].enabled = true;
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_480Cycles;
}
#endif
#ifdef EXTERNAL1_ADC_PIN
if (init->enableExternal1) {
IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN)); //EXTERNAL1_ADC_CHANNEL;
adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_EXTERNAL1].enabled = true;
adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_480Cycles;
adcConfig[ADC_BATTERY].tag = IO_TAG(VBAT_ADC_PIN); //VBAT_ADC_CHANNEL;
}
#endif
#ifdef RSSI_ADC_PIN
if (init->enableRSSI) {
IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN)); //RSSI_ADC_CHANNEL;
adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_RSSI].enabled = true;
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_480Cycles;
adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN); //RSSI_ADC_CHANNEL;
}
#endif
#ifdef EXTERNAL1_ADC_PIN
if (init->enableExternal1) {
adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); //EXTERNAL1_ADC_CHANNEL;
}
#endif
#ifdef CURRENT_METER_ADC_PIN
if (init->enableCurrentMeter) {
IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN)); //CURRENT_METER_ADC_CHANNEL;
adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_CURRENT].enabled = true;
adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_480Cycles;
adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN); //CURRENT_METER_ADC_CHANNEL;
}
#endif
@ -150,6 +130,18 @@ void adcInit(drv_adc_config_t *init)
adcDevice_t adc = adcHardware[device];
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
if (!adcConfig[i].tag)
continue;
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC);
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
adcConfig[i].dmaIndex = configuredAdcChannels++;
adcConfig[i].sampleTime = ADC_SampleTime_480Cycles;
adcConfig[i].enabled = true;
}
RCC_ClockCmd(adc.rccDMA, ENABLE);
RCC_ClockCmd(adc.rccADC, ENABLE);

View File

@ -423,6 +423,9 @@ void i2cInit(I2CDevice device)
I2C_Cmd(i2c->dev, ENABLE);
I2C_Init(i2c->dev, &i2cInit);
I2C_StretchClockCmd(i2c->dev, ENABLE);
// I2C ER Interrupt
nvic.NVIC_IRQChannel = i2c->er_irq;
nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER);

View File

@ -31,6 +31,15 @@
#ifndef SOFT_I2C
#if defined(USE_I2C_PULLUP)
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_UP)
#else
#define IOCFG_I2C IOCFG_AF_OD
#endif
#define I2C_HIGHSPEED_TIMING 0x00500E30 // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
#define I2C_STANDARD_TIMING 0x00E0257A // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
#define I2C_SHORT_TIMEOUT ((uint32_t)0x1000)
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#define I2C_GPIO_AF GPIO_AF_4
@ -83,8 +92,8 @@ void i2cInit(I2CDevice device)
RCC_ClockCmd(i2c->rcc, ENABLE);
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
IOConfigGPIOAF(scl, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4);
IOConfigGPIOAF(sda, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4);
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4);
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4);
I2C_InitTypeDef i2cInit = {
.I2C_Mode = I2C_Mode_I2C,
@ -93,14 +102,13 @@ void i2cInit(I2CDevice device)
.I2C_OwnAddress1 = 0x00,
.I2C_Ack = I2C_Ack_Enable,
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
.I2C_Timing = i2c->overClock ?
0x00500E30 : // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
0x00E0257A, // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
//.I2C_Timing = 0x8000050B;
.I2C_Timing = (i2c->overClock ? I2C_HIGHSPEED_TIMING : I2C_STANDARD_TIMING)
};
I2C_Init(I2Cx, &i2cInit);
I2C_StretchClockCmd(I2Cx, ENABLE);
I2C_Cmd(I2Cx, ENABLE);
}

View File

@ -30,8 +30,6 @@
#include "common/maths.h"
#include "system.h"
#include "gpio.h"
#include "exti.h"
#include "bus_i2c.h"
#include "bus_spi.h"

View File

@ -29,7 +29,8 @@
#include "system.h"
#include "nvic.h"
#include "gpio.h"
#include "io.h"
#include "exti.h"
#include "bus_i2c.h"
#include "light_led.h"
@ -120,14 +121,14 @@ static float magGain[3] = { 1.0f, 1.0f, 1.0f };
static const hmc5883Config_t *hmc5883Config = NULL;
void MAG_DATA_READY_EXTI_Handler(void)
#ifdef USE_MAG_DATA_READY_SIGNAL
static IO_t intIO;
static extiCallbackRec_t hmc5883_extiCallbackRec;
void hmc5883_extiHandler(extiCallbackRec_t* cb)
{
if (EXTI_GetITStatus(hmc5883Config->exti_line) == RESET) {
return;
}
EXTI_ClearITPendingBit(hmc5883Config->exti_line);
UNUSED(cb);
#ifdef DEBUG_MAG_DATA_READY_INTERRUPT
// Measure the delta between calls to the interrupt handler
// currently should be around 65/66 milli seconds / 15hz output rate
@ -143,57 +144,26 @@ void MAG_DATA_READY_EXTI_Handler(void)
lastCalledAt = now;
#endif
}
#endif
static void hmc5883lConfigureDataReadyInterruptHandling(void)
{
#ifdef USE_MAG_DATA_READY_SIGNAL
if (!(hmc5883Config->exti_port_source && hmc5883Config->exti_pin_source)) {
if (!(hmc5883Config->intTag)) {
return;
}
#ifdef STM32F10X
// enable AFIO for EXTI support
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
#endif
#ifdef STM32F303xC
/* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
#endif
#ifdef STM32F10X
gpioExtiLineConfig(hmc5883Config->exti_port_source, hmc5883Config->exti_pin_source);
#endif
#ifdef STM32F303xC
gpioExtiLineConfig(hmc5883Config->exti_port_source, hmc5883Config->exti_pin_source);
#endif
intIO = IOGetByTag(hmc5883Config->intTag);
#ifdef ENSURE_MAG_DATA_READY_IS_HIGH
uint8_t status = GPIO_ReadInputDataBit(hmc5883Config->gpioPort, hmc5883Config->gpioPin);
uint8_t status = IORead(intIO);
if (!status) {
return;
}
#endif
registerExtiCallbackHandler(hmc5883Config->exti_irqn, MAG_DATA_READY_EXTI_Handler);
EXTI_ClearITPendingBit(hmc5883Config->exti_line);
EXTI_InitTypeDef EXTIInit;
EXTIInit.EXTI_Line = hmc5883Config->exti_line;
EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt;
EXTIInit.EXTI_Trigger = EXTI_Trigger_Falling;
EXTIInit.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTIInit);
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = hmc5883Config->exti_irqn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_MAG_DATA_READY);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_MAG_DATA_READY);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
EXTIHandlerInit(&hmc5883_extiCallbackRec, hmc5883_extiHandler);
EXTIConfig(intIO, &hmc5883_extiCallbackRec, NVIC_PRIO_MAG_INT_EXTI, EXTI_Trigger_Rising);
EXTIEnable(intIO, true);
#endif
}
@ -221,25 +191,6 @@ void hmc5883lInit(void)
int32_t xyz_total[3] = { 0, 0, 0 }; // 32 bit totals so they won't overflow.
bool bret = true; // Error indicator
gpio_config_t gpio;
if (hmc5883Config) {
#ifdef STM32F303
if (hmc5883Config->gpioAHBPeripherals) {
RCC_AHBPeriphClockCmd(hmc5883Config->gpioAHBPeripherals, ENABLE);
}
#endif
#ifdef STM32F10X
if (hmc5883Config->gpioAPB2Peripherals) {
RCC_APB2PeriphClockCmd(hmc5883Config->gpioAPB2Peripherals, ENABLE);
}
#endif
gpio.pin = hmc5883Config->gpioPin;
gpio.speed = Speed_2MHz;
gpio.mode = Mode_IN_FLOATING;
gpioInit(hmc5883Config->gpioPort, &gpio);
}
delay(50);
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
// Note that the very first measurement after a gain change maintains the same gain as the previous setting.

View File

@ -17,20 +17,10 @@
#pragma once
typedef struct hmc5883Config_s {
#ifdef STM32F303
uint32_t gpioAHBPeripherals;
#endif
#ifdef STM32F10X
uint32_t gpioAPB2Peripherals;
#endif
uint16_t gpioPin;
GPIO_TypeDef *gpioPort;
#include "io.h"
uint8_t exti_port_source;
uint32_t exti_line;
uint8_t exti_pin_source;
IRQn_Type exti_irqn;
typedef struct hmc5883Config_s {
ioTag_t intTag;
} hmc5883Config_t;
bool hmc5883lDetect(mag_t* mag, const hmc5883Config_t *hmc5883ConfigToUse);

View File

@ -4,48 +4,40 @@
* Created on: 3 aug. 2015
* Author: borisb
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "build_config.h"
#include "common/axis.h"
#include "common/maths.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/gyro_sync.h"
#include "sensors/sensors.h"
#include "sensors/acceleration.h"
#include "config/runtime_config.h"
#include "config/config.h"
extern gyro_t gyro;
uint32_t targetLooptime;
static uint8_t mpuDividerDrops;
bool getMpuDataStatus(gyro_t *gyro)
bool gyroSyncCheckUpdate(const gyro_t *gyro)
{
bool mpuDataStatus;
if (!gyro->intStatus)
return false;
gyro->intStatus(&mpuDataStatus);
return mpuDataStatus;
return gyro->intStatus();
}
bool gyroSyncCheckUpdate(void) {
return getMpuDataStatus(&gyro);
}
#define GYRO_LPF_256HZ 0
#define GYRO_LPF_188HZ 1
#define GYRO_LPF_98HZ 2
#define GYRO_LPF_42HZ 3
#define GYRO_LPF_20HZ 4
#define GYRO_LPF_10HZ 5
#define GYRO_LPF_5HZ 6
#define GYRO_LPF_NONE 7
void gyroUpdateSampleRate(uint8_t lpf, uint8_t gyroSyncDenominator) {
uint32_t gyroSetSampleRate(uint8_t lpf, uint8_t gyroSyncDenominator)
{
int gyroSamplePeriod;
if (!lpf || lpf == 7) {
if (lpf == GYRO_LPF_256HZ || lpf == GYRO_LPF_NONE) {
gyroSamplePeriod = 125;
} else {
gyroSamplePeriod = 1000;
@ -54,9 +46,11 @@ void gyroUpdateSampleRate(uint8_t lpf, uint8_t gyroSyncDenominator) {
// calculate gyro divider and targetLooptime (expected cycleTime)
mpuDividerDrops = gyroSyncDenominator - 1;
targetLooptime = (mpuDividerDrops + 1) * gyroSamplePeriod;
const uint32_t targetLooptime = gyroSyncDenominator * gyroSamplePeriod;
return targetLooptime;
}
uint8_t gyroMPU6xxxGetDividerDrops(void) {
uint8_t gyroMPU6xxxGetDividerDrops(void)
{
return mpuDividerDrops;
}

View File

@ -5,8 +5,7 @@
* Author: borisb
*/
extern uint32_t targetLooptime;
bool gyroSyncCheckUpdate(void);
struct gyro_s;
bool gyroSyncCheckUpdate(const struct gyro_s *gyro);
uint8_t gyroMPU6xxxGetDividerDrops(void);
void gyroUpdateSampleRate(uint8_t lpf, uint8_t gyroSyncDenominator);
uint32_t gyroSetSampleRate(uint8_t lpf, uint8_t gyroSyncDenominator);

View File

@ -52,6 +52,7 @@ typedef uint8_t ioConfig_t; // packed IO configuration
#define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) // TODO
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_25MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
#define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN)
@ -60,6 +61,7 @@ typedef uint8_t ioConfig_t; // packed IO configuration
#define IOCFG_IPD IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_DOWN)
#define IOCFG_IPU IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_UP)
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL)
#define IOCFG_IPU_25 IO_CONFIG(GPIO_Mode_IN, GPIO_Speed_25MHz, 0, GPIO_PuPd_UP)
#elif defined(UNIT_TEST)

View File

@ -80,18 +80,9 @@ void setStripColors(const hsvColor_t *colors)
}
}
void ws2811DMAHandler(DMA_Channel_TypeDef *channel) {
if (DMA_GetFlagStatus(WS2811_DMA_TC_FLAG)) {
ws2811LedDataTransferInProgress = 0;
DMA_Cmd(channel, DISABLE);
DMA_ClearFlag(WS2811_DMA_TC_FLAG);
}
}
void ws2811LedStripInit(void)
{
memset(&ledStripDMABuffer, 0, WS2811_DMA_BUFFER_SIZE);
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler);
ws2811LedStripHardwareInit();
ws2811UpdateStrip();
}
@ -141,12 +132,11 @@ STATIC_UNIT_TESTED void updateLEDDMABuffer(uint8_t componentValue)
*/
void ws2811UpdateStrip(void)
{
static uint32_t waitCounter = 0;
static rgbColor24bpp_t *rgb24;
// wait until previous transfer completes
while(ws2811LedDataTransferInProgress) {
waitCounter++;
// don't wait - risk of infinite block, just get an update next time round
if (ws2811LedDataTransferInProgress) {
return;
}
dmaBufferOffset = 0; // reset buffer memory index

View File

@ -23,35 +23,41 @@
#include "common/color.h"
#include "drivers/light_ws2811strip.h"
#include "nvic.h"
#include "io.h"
#include "dma.h"
#include "timer.h"
#ifdef LED_STRIP
static IO_t ws2811IO = IO_NONE;
bool ws2811Initialised = false;
void ws2811DMAHandler(DMA_Channel_TypeDef *channel)
{
if (DMA_GetFlagStatus(WS2811_DMA_TC_FLAG)) {
ws2811LedDataTransferInProgress = 0;
DMA_Cmd(channel, DISABLE);
DMA_ClearFlag(WS2811_DMA_TC_FLAG);
}
}
void ws2811LedStripHardwareInit(void)
{
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_OCInitTypeDef TIM_OCInitStructure;
GPIO_InitTypeDef GPIO_InitStructure;
DMA_InitTypeDef DMA_InitStructure;
uint16_t prescalerValue;
#ifdef CC3D
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOB, &GPIO_InitStructure);
#else
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler);
/* GPIOA Configuration: TIM3 Channel 1 as alternate function push-pull */
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOA, &GPIO_InitStructure);
#endif
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT);
IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP));
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
/* Compute the prescaler value */
prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1;
/* Time base configuration */
@ -108,16 +114,20 @@ void ws2811LedStripHardwareInit(void)
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
ws2811Initialised = true;
setStripColor(&hsv_white);
ws2811UpdateStrip();
}
void ws2811LedStripDMAEnable(void)
{
if (!ws2811Initialised)
return;
DMA_SetCurrDataCounter(DMA1_Channel6, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
TIM_SetCounter(TIM3, 0);
TIM_Cmd(TIM3, ENABLE);
DMA_Cmd(DMA1_Channel6, ENABLE);
}
#endif

View File

@ -20,51 +20,54 @@
#include <platform.h>
#include "gpio.h"
#include "io.h"
#include "nvic.h"
#include "common/color.h"
#include "drivers/light_ws2811strip.h"
#include "dma.h"
#include "rcc.h"
#include "timer.h"
#ifndef WS2811_GPIO
#define WS2811_GPIO GPIOB
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB
#define WS2811_GPIO_AF GPIO_AF_1
#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1
#define WS2811_PIN_SOURCE GPIO_PinSource8
#ifdef LED_STRIP
#ifndef WS2811_PIN
#define WS2811_PIN PB8 // TIM16_CH1
#define WS2811_TIMER TIM16
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16
#define WS2811_DMA_CHANNEL DMA1_Channel3
#define WS2811_IRQ DMA1_Channel3_IRQn
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
#endif
static IO_t ws2811IO = IO_NONE;
bool ws2811Initialised = false;
void ws2811DMAHandler(DMA_Channel_TypeDef *channel)
{
if (DMA_GetFlagStatus(WS2811_DMA_TC_FLAG)) {
ws2811LedDataTransferInProgress = 0;
DMA_Cmd(channel, DISABLE);
DMA_ClearFlag(WS2811_DMA_TC_FLAG);
}
}
void ws2811LedStripHardwareInit(void)
{
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_OCInitTypeDef TIM_OCInitStructure;
GPIO_InitTypeDef GPIO_InitStructure;
DMA_InitTypeDef DMA_InitStructure;
uint16_t prescalerValue;
RCC_AHBPeriphClockCmd(WS2811_GPIO_AHB_PERIPHERAL, ENABLE);
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler);
GPIO_PinAFConfig(WS2811_GPIO, WS2811_PIN_SOURCE, WS2811_GPIO_AF);
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT);
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER));
/* Configuration alternate function push-pull */
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = WS2811_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(WS2811_GPIO, &GPIO_InitStructure);
RCC_APB2PeriphClockCmd(WS2811_TIMER_APB2_PERIPHERAL, ENABLE);
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
/* Compute the prescaler value */
prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1;
@ -122,16 +125,20 @@ void ws2811LedStripHardwareInit(void)
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
ws2811Initialised = true;
setStripColor(&hsv_white);
ws2811UpdateStrip();
}
void ws2811LedStripDMAEnable(void)
{
if (!ws2811Initialised)
return;
DMA_SetCurrDataCounter(WS2811_DMA_CHANNEL, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
TIM_SetCounter(WS2811_TIMER, 0);
TIM_Cmd(WS2811_TIMER, ENABLE);
DMA_Cmd(WS2811_DMA_CHANNEL, ENABLE);
}
#endif

View File

@ -22,64 +22,121 @@
#include "common/color.h"
#include "light_ws2811strip.h"
#include "dma.h"
#include "nvic.h"
#include "io.h"
#include "system.h"
#include "rcc.h"
#include "timer.h"
#ifdef LED_STRIP
#if !defined(WS2811_PIN)
#define WS2811_PIN PA0
#define WS2811_TIMER TIM5
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER
#define WS2811_DMA_STREAM DMA1_Stream2
#define WS2811_DMA_FLAG DMA_FLAG_TCIF2
#define WS2811_DMA_IT DMA_IT_TCIF2
#define WS2811_DMA_CHANNEL DMA_Channel_6
#define WS2811_DMA_IRQ DMA1_Stream2_IRQn
#define WS2811_TIMER_CHANNEL TIM_Channel_1
#endif
static IO_t ws2811IO = IO_NONE;
static uint16_t timDMASource = 0;
bool ws2811Initialised = false;
void ws2811DMAHandler(DMA_Stream_TypeDef *stream)
{
if (DMA_GetFlagStatus(stream, WS2811_DMA_FLAG)) {
ws2811LedDataTransferInProgress = 0;
DMA_ClearITPendingBit(stream, WS2811_DMA_IT);
DMA_Cmd(stream, DISABLE);
TIM_DMACmd(WS2811_TIMER, timDMASource, DISABLE);
}
}
void ws2811LedStripHardwareInit(void)
{
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_OCInitTypeDef TIM_OCInitStructure;
GPIO_InitTypeDef GPIO_InitStructure;
DMA_InitTypeDef DMA_InitStructure;
uint16_t prescalerValue;
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE);
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE);
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource0, GPIO_AF_TIM5);
IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT);
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER));
// Stop timer
TIM_Cmd(TIM5, DISABLE);
TIM_Cmd(WS2811_TIMER, DISABLE);
/* Compute the prescaler value */
prescalerValue = (uint16_t) (SystemCoreClock / 2 / 84000000) - 1;
prescalerValue = (uint16_t)(SystemCoreClock / 2 / 84000000) - 1;
/* Time base configuration */
TIM_TimeBaseStructure.TIM_Period = 104; // 800kHz
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseInit(TIM5, &TIM_TimeBaseStructure);
TIM_TimeBaseInit(WS2811_TIMER, &TIM_TimeBaseStructure);
/* PWM1 Mode configuration: Channel1 */
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Reset;
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Set;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCNPolarity_High;
TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_High;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
TIM_OCInitStructure.TIM_Pulse = 0;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
TIM_OC1Init(TIM5, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(TIM5, TIM_OCPreload_Enable);
TIM_Cmd(TIM5, ENABLE);
uint32_t channelAddress = 0;
switch (WS2811_TIMER_CHANNEL) {
case TIM_Channel_1:
TIM_OC1Init(WS2811_TIMER, &TIM_OCInitStructure);
timDMASource = TIM_DMA_CC1;
channelAddress = (uint32_t)(&WS2811_TIMER->CCR1);
TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
break;
case TIM_Channel_2:
TIM_OC2Init(WS2811_TIMER, &TIM_OCInitStructure);
timDMASource = TIM_DMA_CC2;
channelAddress = (uint32_t)(&WS2811_TIMER->CCR2);
TIM_OC2PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
break;
case TIM_Channel_3:
TIM_OC3Init(WS2811_TIMER, &TIM_OCInitStructure);
timDMASource = TIM_DMA_CC3;
channelAddress = (uint32_t)(&WS2811_TIMER->CCR3);
TIM_OC3PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
break;
case TIM_Channel_4:
TIM_OC4Init(WS2811_TIMER, &TIM_OCInitStructure);
timDMASource = TIM_DMA_CC4;
channelAddress = (uint32_t)(&WS2811_TIMER->CCR4);
TIM_OC4PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
break;
}
TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE);
TIM_ARRPreloadConfig(WS2811_TIMER, ENABLE);
TIM_CCxCmd(WS2811_TIMER, WS2811_TIMER_CHANNEL, TIM_CCx_Enable);
TIM_Cmd(WS2811_TIMER, ENABLE);
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler);
/* configure DMA */
/* DMA1 Channel Config */
DMA_Cmd(DMA1_Stream2, DISABLE); // disable DMA channel 6
DMA_DeInit(DMA1_Stream2);
DMA_Cmd(WS2811_DMA_STREAM, DISABLE);
DMA_DeInit(WS2811_DMA_STREAM);
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_Channel = DMA_Channel_6;
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&(TIM5->CCR1);
DMA_InitStructure.DMA_Channel = WS2811_DMA_CHANNEL;
DMA_InitStructure.DMA_PeripheralBaseAddr = channelAddress;
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)ledStripDMABuffer;
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
@ -93,38 +150,36 @@ void ws2811LedStripHardwareInit(void)
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull;
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
DMA_Init(DMA1_Stream2, &DMA_InitStructure);
DMA_ITConfig(DMA1_Stream2, DMA_IT_TC, ENABLE);
DMA_ClearITPendingBit(DMA1_Stream2, DMA_IT_TCIF2); // clear DMA1 Channel 6 transfer complete flag
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE);
DMA_Init(WS2811_DMA_STREAM, &DMA_InitStructure);
DMA_ITConfig(WS2811_DMA_STREAM, DMA_IT_TC, ENABLE);
DMA_ClearITPendingBit(WS2811_DMA_STREAM, WS2811_DMA_IT);
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = DMA1_Stream2_IRQn;
NVIC_InitStructure.NVIC_IRQChannel = WS2811_DMA_IRQ;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_WS2811_DMA);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
ws2811Initialised = true;
setStripColor(&hsv_white);
ws2811UpdateStrip();
}
void DMA1_Stream2_IRQHandler(void)
{
if (DMA_GetFlagStatus(DMA1_Stream2, DMA_FLAG_TCIF2)) {
ws2811LedDataTransferInProgress = 0;
DMA_Cmd(DMA1_Stream2, DISABLE);
TIM_DMACmd(TIM5, TIM_DMA_CC1, DISABLE);
DMA_ClearITPendingBit(DMA1_Stream2, DMA_IT_TCIF2);
}
}
void ws2811LedStripDMAEnable(void)
{
DMA_SetCurrDataCounter(DMA1_Stream2, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
TIM_SetCounter(TIM5, 0);
DMA_Cmd(DMA1_Stream2, ENABLE);
TIM_DMACmd(TIM5, TIM_DMA_CC1, ENABLE);
if (!ws2811Initialised)
return;
DMA_SetCurrDataCounter(WS2811_DMA_STREAM, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
TIM_SetCounter(WS2811_TIMER, 0);
DMA_Cmd(WS2811_DMA_STREAM, ENABLE);
TIM_DMACmd(WS2811_TIMER, timDMASource, ENABLE);
}
#endif

View File

@ -157,33 +157,33 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
continue;
#endif
#ifdef LED_STRIP_TIMER
#ifdef WS2811_TIMER
// skip LED Strip output
if (init->useLEDStrip) {
if (timerHardwarePtr->tim == LED_STRIP_TIMER)
if (timerHardwarePtr->tim == WS2811_TIMER)
continue;
#if defined(STM32F303xC) && defined(WS2811_GPIO) && defined(WS2811_PIN_SOURCE)
if (CheckGPIOPinSource(timerHardwarePtr->tag, WS2811_GPIO, WS2811_PIN_SOURCE))
#if defined(STM32F303xC) && defined(WS2811_PIN)
if (timerHardwarePtr->tag == IO_TAG(WS2811_PIN))
continue;
#endif
}
#endif
#ifdef VBAT_ADC_GPIO
if (init->useVbat && CheckGPIOPin(timerHardwarePtr->tag, VBAT_ADC_GPIO, VBAT_ADC_GPIO_PIN)) {
#ifdef VBAT_ADC_PIN
if (init->useVbat && timerHardwarePtr->tag == IO_TAG(VBAT_ADC_PIN)) {
continue;
}
#endif
#ifdef RSSI_ADC_GPIO
if (init->useRSSIADC && CheckGPIOPin(timerHardwarePtr->tag, RSSI_ADC_GPIO, RSSI_ADC_GPIO_PIN)) {
if (init->useRSSIADC && timerHardwarePtr->tag == IO_TAG(RSSI_ADC_PIN)) {
continue;
}
#endif
#ifdef CURRENT_METER_ADC_GPIO
if (init->useCurrentMeterADC && CheckGPIOPin(timerHardwarePtr->tag, CURRENT_METER_ADC_GPIO, CURRENT_METER_ADC_GPIO_PIN)) {
if (init->useCurrentMeterADC && timerHardwarePtr->tag == IO_TAG(CURRENT_METER_ADC_PIN)) {
continue;
}
#endif
@ -274,7 +274,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
}
if (init->useChannelForwarding && !init->airplane) {
#if defined(NAZE) && defined(LED_STRIP_TIMER)
#if defined(NAZE) && defined(WS2811_TIMER)
// if LED strip is active, PWM5-8 are unavailable, so map AUX1+AUX2 to PWM13+PWM14
if (init->useLEDStrip) {
if (timerIndex >= PWM13 && timerIndex <= PWM14) {

View File

@ -93,8 +93,6 @@ typedef enum {
PWM_PF_OUTPUT_PROTOCOL_ONESHOT = (1 << 4)
} pwmPortFlags_e;
enum {PWM_INVERTED = 1};
typedef struct pwmPortConfiguration_s {
uint8_t index;
pwmPortFlags_e flags;

View File

@ -97,9 +97,9 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
configTimeBase(timerHardware->tim, period, mhz);
pwmGPIOConfig(timerHardware->tag, IOCFG_AF_PP);
pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->outputInverted);
pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED);
if (timerHardware->outputEnable) {
if (timerHardware->output & TIMER_OUTPUT_ENABLED) {
TIM_CtrlPWMOutputs(timerHardware->tim, ENABLE);
}
TIM_Cmd(timerHardware->tim, ENABLE);

View File

@ -7,7 +7,7 @@ void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState)
int tag = periphTag >> 5;
uint32_t mask = 1 << (periphTag & 0x1f);
switch (tag) {
#if defined(STM32F303xC)
#if defined(STM32F3) || defined(STM32F1)
case RCC_AHB:
RCC_AHBPeriphClockCmd(mask, NewState);
break;
@ -18,7 +18,7 @@ void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState)
case RCC_APB1:
RCC_APB1PeriphClockCmd(mask, NewState);
break;
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
#if defined(STM32F4)
case RCC_AHB1:
RCC_AHB1PeriphClockCmd(mask, NewState);
break;
@ -31,7 +31,7 @@ void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState)
int tag = periphTag >> 5;
uint32_t mask = 1 << (periphTag & 0x1f);
switch (tag) {
#if defined(STM32F303xC)
#if defined(STM32F3) || defined(STM32F10X_CL)
case RCC_AHB:
RCC_AHBPeriphResetCmd(mask, NewState);
break;
@ -42,7 +42,7 @@ void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState)
case RCC_APB1:
RCC_APB1PeriphResetCmd(mask, NewState);
break;
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
#if defined(STM32F4)
case RCC_AHB1:
RCC_AHB1PeriphResetCmd(mask, NewState);
break;

View File

@ -22,4 +22,4 @@ typedef void (*sensorInitFuncPtr)(void); // sensor init proto
typedef bool (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
typedef void (*sensorAccInitFuncPtr)(struct acc_s *acc); // sensor init prototype
typedef void (*sensorGyroInitFuncPtr)(uint8_t lpf); // gyro sensor init prototype
typedef void (*sensorInterruptFuncPtr)(bool *data); // sensor Interrupt Data Ready
typedef bool (*sensorInterruptFuncPtr)(void); // sensor Interrupt Data Ready

View File

@ -56,7 +56,7 @@ void serialWriteBuf(serialPort_t *instance, uint8_t *data, int count)
}
}
uint8_t serialRxBytesWaiting(serialPort_t *instance)
uint32_t serialRxBytesWaiting(serialPort_t *instance)
{
return instance->vTable->serialTotalRxWaiting(instance);
}

View File

@ -81,7 +81,7 @@ struct serialPortVTable {
};
void serialWrite(serialPort_t *instance, uint8_t ch);
uint8_t serialRxBytesWaiting(serialPort_t *instance);
uint32_t serialRxBytesWaiting(serialPort_t *instance);
uint8_t serialTxBytesFree(serialPort_t *instance);
void serialWriteBuf(serialPort_t *instance, uint8_t *data, int count);
uint8_t serialRead(serialPort_t *instance);

View File

@ -408,7 +408,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
}
}
uint8_t softSerialRxBytesWaiting(serialPort_t *instance)
uint32_t softSerialRxBytesWaiting(serialPort_t *instance)
{
if ((instance->mode & MODE_RX) == 0) {
return 0;

View File

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

View File

@ -42,6 +42,7 @@ void systemReset(void);
void systemResetToBootloader(void);
bool isMPUSoftReset(void);
void cycleCounterInit(void);
void checkForBootLoaderRequest(void);
void enableGPIOPowerUsageAndNoiseReductions(void);
// current crystal frequency - 8 or 12MHz

View File

@ -37,7 +37,8 @@ void systemReset(void)
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
}
void systemResetToBootloader(void) {
void systemResetToBootloader(void)
{
// 1FFFF000 -> 20000200 -> SP
// 1FFFF004 -> 1FFFF021 -> PC
@ -68,6 +69,8 @@ bool isMPUSoftReset(void)
void systemInit(void)
{
checkForBootLoaderRequest();
SetSysClock(false);
#ifdef CC3D
@ -110,3 +113,6 @@ void systemInit(void)
SysTick_Config(SystemCoreClock / 1000);
}
void checkForBootLoaderRequest(void)
{
}

View File

@ -35,7 +35,8 @@ void systemReset(void)
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
}
void systemResetToBootloader(void) {
void systemResetToBootloader(void)
{
// 1FFFF000 -> 20000200 -> SP
// 1FFFF004 -> 1FFFF021 -> PC
@ -82,6 +83,8 @@ bool isMPUSoftReset(void)
void systemInit(void)
{
checkForBootLoaderRequest();
// Enable FPU
SCB->CPACR = (0x3 << (10 * 2)) | (0x3 << (11 * 2));
SetSysClock();
@ -102,3 +105,7 @@ void systemInit(void)
// SysTick
SysTick_Config(SystemCoreClock / 1000);
}
void checkForBootLoaderRequest(void)
{
}

View File

@ -169,6 +169,8 @@ bool isMPUSoftReset(void)
void systemInit(void)
{
checkForBootLoaderRequest();
SetSysClock();
// Configure NVIC preempt/priority groups
@ -194,3 +196,18 @@ void systemInit(void)
SysTick_Config(SystemCoreClock / 1000);
}
void(*bootJump)(void);
void checkForBootLoaderRequest(void)
{
if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) {
*((uint32_t *)0x2001FFFC) = 0x0;
__enable_irq();
__set_MSP(0x20001000);
bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004));
bootJump();
while (1);
}
}

View File

@ -17,7 +17,6 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include "platform.h"
@ -26,7 +25,6 @@
#include "nvic.h"
#include "gpio.h"
#include "gpio.h"
#include "rcc.h"
#include "system.h"
@ -153,6 +151,18 @@ rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
return 0;
}
#if defined(STM32F3) || defined(STM32F4)
uint8_t timerGPIOAF(TIM_TypeDef *tim)
{
for (uint8_t i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
if (timerDefinitions[i].TIMx == tim) {
return timerDefinitions[i].alternateFunction;
}
}
return 0;
}
#endif
void timerNVICConfigure(uint8_t irq)
{
NVIC_InitTypeDef NVIC_InitStructure;
@ -458,7 +468,7 @@ void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHig
if(outEnable) {
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Inactive;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
if (timHw->outputInverted) {
if (timHw->output & TIMER_OUTPUT_INVERTED) {
stateHigh = !stateHigh;
}
TIM_OCInitStructure.TIM_OCPolarity = stateHigh ? TIM_OCPolarity_High : TIM_OCPolarity_Low;

View File

@ -69,6 +69,9 @@ typedef struct timerOvrHandlerRec_s {
typedef struct timerDef_s {
TIM_TypeDef *TIMx;
rccPeriphTag_t rcc;
#if defined(STM32F3) || defined(STM32F4)
uint8_t alternateFunction;
#endif
} timerDef_t;
typedef struct timerHardware_s {
@ -76,14 +79,18 @@ typedef struct timerHardware_s {
ioTag_t tag;
uint8_t channel;
uint8_t irq;
uint8_t outputEnable;
uint8_t output;
ioConfig_t ioMode;
#if defined(STM32F3) || defined(STM32F4)
uint8_t alternateFunction;
#endif
uint8_t outputInverted;
} timerHardware_t;
enum {
TIMER_OUTPUT_ENABLED = 0x01,
TIMER_OUTPUT_INVERTED = 0x02
};
#ifdef STM32F1
#if defined(STM32F10X_XL) || defined(STM32F10X_HD_VL)
#define HARDWARE_TIMER_DEFINITION_COUNT 14
@ -148,3 +155,7 @@ void timerForceOverflow(TIM_TypeDef *tim);
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz); // TODO - just for migration
rccPeriphTag_t timerRCC(TIM_TypeDef *tim);
#if defined(STM32F3) || defined(STM32F4)
uint8_t timerGPIOAF(TIM_TypeDef *tim);
#endif

View File

@ -67,8 +67,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
tmp = (uint32_t) TIMx;
tmp += CCMR_Offset;
if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3))
{
if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) {
tmp += (TIM_Channel>>1);
/* Reset the OCxM bits in the CCMRx register */
@ -76,10 +75,8 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
/* Configure the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp |= TIM_OCMode;
}
else
{
tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1;
} else {
tmp += (uint16_t)(TIM_Channel - (uint16_t)4) >> (uint16_t)1;
/* Reset the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC2M);

View File

@ -10,16 +10,16 @@
#include "timer.h"
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1) },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2) },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3) },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4) },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6) },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7) },
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8) },
{ .TIMx = TIM15, .rcc = RCC_APB2(TIM15) },
{ .TIMx = TIM16, .rcc = RCC_APB2(TIM16) },
{ .TIMx = TIM17, .rcc = RCC_APB2(TIM17) },
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_6 },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_1 },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_2 },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_10 },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 },
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_5 },
{ .TIMx = TIM15, .rcc = RCC_APB2(TIM15), GPIO_AF_9 },
{ .TIMx = TIM16, .rcc = RCC_APB2(TIM16), GPIO_AF_1 },
{ .TIMx = TIM17, .rcc = RCC_APB2(TIM17), GPIO_AF_1 },
};
@ -77,7 +77,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t
/* Configure the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp |= TIM_OCMode;
} else {
tmp += (uint32_t)(TIM_Channel - (uint32_t)4)>> (uint32_t)1;
tmp += (uint32_t)(TIM_Channel - (uint32_t)4) >> (uint32_t)1;
/* Reset the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp &= CCMR_OC24M_MASK;

View File

@ -35,20 +35,20 @@
#define CCMR_Offset ((uint16_t)0x0018)
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1) },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2) },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3) },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4) },
{ .TIMx = TIM5, .rcc = RCC_APB1(TIM5) },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6) },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7) },
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8) },
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9) },
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10) },
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11) },
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12) },
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13) },
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14) },
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_TIM1 },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_TIM2 },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_TIM3 },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_TIM4 },
{ .TIMx = TIM5, .rcc = RCC_APB1(TIM5), GPIO_AF_TIM5 },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 },
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_TIM8 },
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9), GPIO_AF_TIM9 },
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10), GPIO_AF_TIM10 },
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11), GPIO_AF_TIM11 },
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12), GPIO_AF_TIM12 },
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13), GPIO_AF_TIM13 },
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14), GPIO_AF_TIM14 },
};
void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode)
@ -63,8 +63,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
tmp = (uint32_t) TIMx;
tmp += CCMR_Offset;
if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3))
{
if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) {
tmp += (TIM_Channel>>1);
/* Reset the OCxM bits in the CCMRx register */
@ -72,9 +71,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
/* Configure the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp |= TIM_OCMode;
}
else
{
} else {
tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1;
/* Reset the OCxM bits in the CCMRx register */

View File

@ -28,7 +28,6 @@
#include "debug.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/system.h"
#include "drivers/sensor.h"

View File

@ -36,7 +36,6 @@
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/system.h"
#include "drivers/gyro_sync.h"
#include "rx/rx.h"
@ -947,7 +946,7 @@ void filterServos(void)
#ifdef USE_SERVOS
static int16_t servoIdx;
static bool servoFilterIsSet;
static biquad_t servoFilterState[MAX_SUPPORTED_SERVOS];
static biquadFilter_t servoFilter[MAX_SUPPORTED_SERVOS];
#if defined(MIXER_DEBUG)
uint32_t startTime = micros();
@ -956,11 +955,11 @@ void filterServos(void)
if (mixerConfig->servo_lowpass_enable) {
for (servoIdx = 0; servoIdx < MAX_SUPPORTED_SERVOS; servoIdx++) {
if (!servoFilterIsSet) {
BiQuadNewLpf(mixerConfig->servo_lowpass_freq, &servoFilterState[servoIdx], targetPidLooptime);
biquadFilterInit(&servoFilter[servoIdx], mixerConfig->servo_lowpass_freq, targetPidLooptime);
servoFilterIsSet = true;
}
servo[servoIdx] = lrintf(applyBiQuadFilter((float) servo[servoIdx], &servoFilterState[servoIdx]));
servo[servoIdx] = lrintf(biquadFilterApply(&servoFilter[servoIdx], (float)servo[servoIdx]));
// Sanity check
servo[servoIdx] = constrain(servo[servoIdx], servoConf[servoIdx].min, servoConf[servoIdx].max);
}

View File

@ -29,7 +29,6 @@
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/gyro_sync.h"
#include "drivers/accgyro.h"
#include "sensors/sensors.h"
@ -74,7 +73,7 @@ pidControllerFuncPtr pid_controller = pidInteger; // which pid controller are we
void setTargetPidLooptime(uint8_t pidProcessDenom)
{
targetPidLooptime = targetLooptime * pidProcessDenom;
targetPidLooptime = gyro.targetLooptime * pidProcessDenom;
}
uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate)
@ -113,8 +112,8 @@ float getdT (void)
const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
static filterStatePt1_t deltaFilterState[3];
static filterStatePt1_t yawFilterState;
static pt1Filter_t deltaFilter[3];
static pt1Filter_t yawFilter;
#ifndef SKIP_PID_LUXFLOAT
static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
@ -206,7 +205,7 @@ static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclinat
//-----calculate D-term
if (axis == YAW) {
if (pidProfile->yaw_lpf_hz) PTerm = filterApplyPt1(PTerm, &yawFilterState, pidProfile->yaw_lpf_hz, getdT());
if (pidProfile->yaw_lpf_hz) PTerm = pt1FilterApply4(&yawFilter, PTerm, pidProfile->yaw_lpf_hz, getdT());
axisPID[axis] = lrintf(PTerm + ITerm);
@ -231,7 +230,7 @@ static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclinat
delta *= (1.0f / getdT());
// Filter delta
if (pidProfile->dterm_lpf_hz) delta = filterApplyPt1(delta, &deltaFilterState[axis], pidProfile->dterm_lpf_hz, getdT());
if (pidProfile->dterm_lpf_hz) delta = pt1FilterApply4(&deltaFilter[axis], delta, pidProfile->dterm_lpf_hz, getdT());
DTerm = constrainf(luxDTermScale * delta * (float)pidProfile->D8[axis] * tpaFactor, -300.0f, 300.0f);
@ -345,7 +344,7 @@ static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclin
//-----calculate D-term
if (axis == YAW) {
if (pidProfile->yaw_lpf_hz) PTerm = filterApplyPt1(PTerm, &yawFilterState, pidProfile->yaw_lpf_hz, getdT());
if (pidProfile->yaw_lpf_hz) PTerm = pt1FilterApply4(&yawFilter, PTerm, pidProfile->yaw_lpf_hz, getdT());
axisPID[axis] = PTerm + ITerm;
@ -370,7 +369,7 @@ static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclin
delta = (delta * ((uint16_t) 0xFFFF / ((uint16_t)targetPidLooptime >> 4))) >> 5;
// Filter delta
if (pidProfile->dterm_lpf_hz) delta = filterApplyPt1((float)delta, &deltaFilterState[axis], pidProfile->dterm_lpf_hz, getdT());
if (pidProfile->dterm_lpf_hz) delta = pt1FilterApply4(&deltaFilter[axis], (float)delta, pidProfile->dterm_lpf_hz, getdT());
DTerm = (delta * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8;

View File

@ -440,7 +440,7 @@ void updateLedCount(void)
}
}
void reevalulateLedConfig(void)
void reevaluateLedConfig(void)
{
updateLedCount();
determineLedStripDimensions();
@ -534,7 +534,7 @@ bool parseLedStripConfig(uint8_t ledIndex, const char *config)
memset(ledConfig, 0, sizeof(ledConfig_t));
}
reevalulateLedConfig();
reevaluateLedConfig();
return ok;
}
@ -1095,7 +1095,7 @@ void applyDefaultLedStripConfig(ledConfig_t *ledConfigs)
memset(ledConfigs, 0, MAX_LED_STRIP_LENGTH * sizeof(ledConfig_t));
memcpy(ledConfigs, &defaultLedStripConfig, sizeof(defaultLedStripConfig));
reevalulateLedConfig();
reevaluateLedConfig();
}
void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse)
@ -1107,7 +1107,7 @@ void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse)
void ledStripEnable(void)
{
reevalulateLedConfig();
reevaluateLedConfig();
ledStripInitialised = true;
ws2811LedStripInit();

View File

@ -94,4 +94,4 @@ bool parseColor(uint8_t index, const char *colorConfig);
void applyDefaultColors(hsvColor_t *colors, uint8_t colorCount);
void ledStripEnable(void);
void reevalulateLedConfig(void);
void reevaluateLedConfig(void);

View File

@ -52,7 +52,6 @@
#include "drivers/inverter.h"
#include "drivers/flash_m25p16.h"
#include "drivers/sonar_hcsr04.h"
#include "drivers/gyro_sync.h"
#include "drivers/usb_io.h"
#include "drivers/transponder_ir.h"
#include "drivers/sdcard.h"

View File

@ -34,7 +34,6 @@
#include "drivers/system.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/gyro_sync.h"
#include "sensors/barometer.h"
#include "sensors/battery.h"
@ -210,7 +209,7 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat
if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) {
// GYRO calibration
gyroSetCalibrationCycles(calculateCalibratingCycles());
gyroSetCalibrationCycles();
#ifdef GPS
if (feature(FEATURE_GPS)) {

View File

@ -44,15 +44,15 @@
#define USE_TXRX_LED
#if defined(USE_TXRX_LED) && defined(LED0)
# define RX_LED_OFF LED0_OFF
# define RX_LED_ON LED0_ON
# ifdef LED1
# define TX_LED_OFF LED1_OFF
# define TX_LED_ON LED1_ON
# else
# define TX_LED_OFF LED0_OFF
# define TX_LED_ON LED0_ON
# endif
#define RX_LED_OFF LED0_OFF
#define RX_LED_ON LED0_ON
#ifdef LED1
#define TX_LED_OFF LED1_OFF
#define TX_LED_ON LED1_ON
#else
#define TX_LED_OFF LED0_OFF
#define TX_LED_ON LED0_ON
#endif
#else
# define RX_LED_OFF do {} while(0)
# define RX_LED_ON do {} while(0)
@ -330,6 +330,7 @@ void esc4wayProcess(serialPort_t *serial)
while(!esc4wayExitRequested) {
// restart looking for new sequence from host
crcIn = 0;
uint8_t esc = readByteCrc();
if(esc != cmd_Local_Escape)
continue; // wait for sync character
@ -348,7 +349,6 @@ void esc4wayProcess(serialPort_t *serial)
paramBuf[i] = readByteCrc();
readByteCrc(); readByteCrc(); // update input CRC
RX_LED_OFF;
outLen = 0; // output handling code will send single zero byte if necessary
replyAck = esc4wayAck_OK;
@ -356,8 +356,10 @@ void esc4wayProcess(serialPort_t *serial)
if(crcIn != 0) // CRC of correct message == 0
replyAck = esc4wayAck_I_INVALID_CRC;
TX_LED_ON;
if (replyAck == esc4wayAck_OK)
replyAck = esc4wayProcessCmd(command, addr, paramBuf, inLen, &outLen);
RX_LED_OFF;
// send single '\0' byte is output when length is zero (len ==0 -> 256 bytes)
if(!outLen) {
@ -366,14 +368,13 @@ void esc4wayProcess(serialPort_t *serial)
}
crcOut = 0;
TX_LED_ON;
serialBeginWrite(port);
writeByteCrc(cmd_Remote_Escape);
writeByteCrc(command);
writeByteCrc(addr >> 8);
writeByteCrc(addr & 0xff);
writeByteCrc(outLen & 0xff); // only low byte is send, 0x00 -> 256B
for(int i = 0; i < outLen; i++)
for(int i = 0; i < outLen % 0x100; i++)
writeByteCrc(paramBuf[i]);
writeByteCrc(replyAck);
writeByte(crcOut >> 8);

View File

@ -238,7 +238,7 @@ void BL_SendCMDRunRestartBootloader(void)
static uint8_t BL_SendCMDSetAddress(ioMem_t *pMem) //supports only 16 bit Adr
{
// skip if adr == 0xFFFF
if((pMem->addr == 0xffff))
if(pMem->addr == 0xffff)
return 1;
uint8_t sCMD[] = {CMD_SET_ADDRESS, 0, pMem->addr >> 8, pMem->addr & 0xff };
BL_SendBuf(sCMD, sizeof(sCMD), true);

View File

@ -48,7 +48,6 @@
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/sdcard.h"
#include "drivers/gyro_sync.h"
#include "drivers/buf_writer.h"
@ -113,6 +112,7 @@ static void cliRxFail(char *cmdline);
static void cliAdjustmentRange(char *cmdline);
static void cliMotorMix(char *cmdline);
static void cliDefaults(char *cmdline);
void cliDfu(char *cmdLine);
static void cliDump(char *cmdLine);
void cliDumpProfile(uint8_t profileIndex);
void cliDumpRateProfile(uint8_t rateProfileIndex) ;
@ -123,6 +123,7 @@ static void cliPlaySound(char *cmdline);
static void cliProfile(char *cmdline);
static void cliRateProfile(char *cmdline);
static void cliReboot(void);
static void cliRebootEx(bool bootLoader);
static void cliSave(char *cmdline);
static void cliSerial(char *cmdline);
#ifndef SKIP_SERIAL_PASSTHROUGH
@ -264,8 +265,8 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
#endif
CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
CLI_COMMAND_DEF("dump", "dump configuration",
"[master|profile]", cliDump),
CLI_COMMAND_DEF("dfu", "DFU mode on reboot", NULL, cliDfu),
CLI_COMMAND_DEF("dump", "dump configuration", "[master|profile]", cliDump),
CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
CLI_COMMAND_DEF("feature", "configure features",
"list\r\n"
@ -2564,11 +2565,20 @@ static void cliRateProfile(char *cmdline) {
}
static void cliReboot(void)
{
cliRebootEx(false);
}
static void cliRebootEx(bool bootLoader)
{
cliPrint("\r\nRebooting");
bufWriterFlush(cliWriter);
waitForSerialPortToFinishTransmitting(cliPort);
stopMotors();
if (bootLoader) {
systemResetToBootloader();
return;
}
systemReset();
}
@ -3108,6 +3118,13 @@ static void cliResource(char *cmdline)
}
}
void cliDfu(char *cmdLine)
{
UNUSED(cmdLine);
cliPrint("\r\nRestarting in DFU mode");
cliRebootEx(true);
}
void cliInit(serialConfig_t *serialConfig)
{
UNUSED(serialConfig);

View File

@ -40,7 +40,6 @@
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/gyro_sync.h"
#include "drivers/sdcard.h"
#include "drivers/buf_writer.h"
#include "drivers/max7456.h"
@ -109,8 +108,8 @@ void setGyroSamplingSpeed(uint16_t looptime) {
uint16_t gyroSampleRate = 1000;
uint8_t maxDivider = 1;
if (looptime != targetLooptime || looptime == 0) {
if (looptime == 0) looptime = targetLooptime; // needed for pid controller changes
if (looptime != gyro.targetLooptime || looptime == 0) {
if (looptime == 0) looptime = gyro.targetLooptime; // needed for pid controller changes
#ifdef STM32F303xC
if (looptime < 1000) {
masterConfig.gyro_lpf = 0;
@ -854,7 +853,7 @@ static bool processOutCommand(uint8_t cmdMSP)
break;
case MSP_LOOP_TIME:
headSerialReply(2);
serialize16((uint16_t)targetLooptime);
serialize16((uint16_t)gyro.targetLooptime);
break;
case MSP_RC_TUNING:
headSerialReply(11);
@ -1808,7 +1807,7 @@ static bool processInCommand(void)
ledConfig->color = read8();
reevalulateLedConfig();
reevaluateLedConfig();
}
break;
#endif

View File

@ -17,11 +17,11 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include "platform.h"
#include "common/axis.h"
#include "common/color.h"
#include "common/maths.h"
@ -49,7 +49,6 @@
#include "drivers/inverter.h"
#include "drivers/flash_m25p16.h"
#include "drivers/sonar_hcsr04.h"
#include "drivers/gyro_sync.h"
#include "drivers/sdcard.h"
#include "drivers/usb_io.h"
#include "drivers/transponder_ir.h"
@ -153,9 +152,6 @@ static uint8_t systemState = SYSTEM_STATE_INITIALISING;
void init(void)
{
uint8_t i;
drv_pwm_config_t pwm_params;
printfSupportInit();
initEEPROM();
@ -260,6 +256,7 @@ void init(void)
mixerInit(masterConfig.mixerMode, masterConfig.customMotorMixer);
#endif
drv_pwm_config_t pwm_params;
memset(&pwm_params, 0, sizeof(pwm_params));
#ifdef SONAR
@ -333,6 +330,7 @@ void init(void)
#endif
pwmRxInit(masterConfig.inputFilteringMode);
// pwmInit() needs to be called as soon as possible for ESC compatibility reasons
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
mixerUsePWMOutputConfiguration(pwmOutputConfiguration, use_unsyncedPwm);
@ -504,7 +502,7 @@ void init(void)
LED0_OFF;
LED2_OFF;
for (i = 0; i < 10; i++) {
for (int i = 0; i < 10; i++) {
LED1_TOGGLE;
LED0_TOGGLE;
delay(25);
@ -626,7 +624,7 @@ void init(void)
if (masterConfig.mixerMode == MIXER_GIMBAL) {
accSetCalibrationCycles(CALIBRATING_ACC_CYCLES);
}
gyroSetCalibrationCycles(calculateCalibratingCycles());
gyroSetCalibrationCycles();
#ifdef BARO
baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES);
#endif
@ -694,12 +692,12 @@ void main_init(void)
/* Setup scheduler */
schedulerInit();
rescheduleTask(TASK_GYROPID, targetLooptime);
rescheduleTask(TASK_GYROPID, gyro.targetLooptime);
setTaskEnabled(TASK_GYROPID, true);
if(sensors(SENSOR_ACC)) {
setTaskEnabled(TASK_ACCEL, true);
switch(targetLooptime) { // Switch statement kept in place to change acc rates in the future
switch(gyro.targetLooptime) { // Switch statement kept in place to change acc rates in the future
case(500):
case(375):
case(250):

View File

@ -377,7 +377,7 @@ void mwArm(void)
static bool firstArmingCalibrationWasCompleted;
if (masterConfig.gyro_cal_on_first_arm && !firstArmingCalibrationWasCompleted) {
gyroSetCalibrationCycles(calculateCalibratingCycles());
gyroSetCalibrationCycles();
armingCalibrationWasInitialised = true;
firstArmingCalibrationWasCompleted = true;
}
@ -698,6 +698,8 @@ void subTaskMainSubprocesses(void) {
#endif
#if defined(BARO) || defined(SONAR)
// updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState
updateRcCommands();
if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) {
if (FLIGHT_MODE(BARO_MODE) || FLIGHT_MODE(SONAR_MODE)) {
applyAltHold(&masterConfig.airplaneConfig);
@ -800,7 +802,7 @@ void taskMainPidLoopCheck(void)
const uint32_t startTime = micros();
while (true) {
if (gyroSyncCheckUpdate() || ((currentDeltaTime + (micros() - previousTime)) >= (targetLooptime + GYRO_WATCHDOG_DELAY))) {
if (gyroSyncCheckUpdate(&gyro) || ((currentDeltaTime + (micros() - previousTime)) >= (gyro.targetLooptime + GYRO_WATCHDOG_DELAY))) {
static uint8_t pidUpdateCountdown;
if (debugMode == DEBUG_PIDLOOP) {debug[0] = micros() - startTime;} // time spent busy waiting
@ -878,8 +880,10 @@ void taskUpdateRxMain(void)
processRx();
isRXDataNew = true;
#if !defined(BARO) && !defined(SONAR)
// updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState
updateRcCommands();
#endif
updateLEDs();
#ifdef BARO

View File

@ -41,7 +41,6 @@
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/system.h"
#include "drivers/gyro_sync.h"
#include "rx/pwm.h"
#include "rx/sbus.h"
#include "rx/spektrum.h"

View File

@ -168,8 +168,8 @@ cfTask_t cfTasks[TASK_COUNT] = {
[TASK_LEDSTRIP] = {
.taskName = "LEDSTRIP",
.taskFunc = taskLedStrip,
.desiredPeriod = 1000000 / 100, // 100 Hz
.staticPriority = TASK_PRIORITY_IDLE,
.desiredPeriod = 1000000 / 10, // 10 Hz
.staticPriority = TASK_PRIORITY_LOW,
},
#endif

View File

@ -28,7 +28,6 @@
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/system.h"
#include "drivers/gyro_sync.h"
#include "sensors/battery.h"
#include "sensors/sensors.h"
@ -45,10 +44,9 @@ acc_t acc; // acc access functions
sensor_align_e accAlign = 0;
uint32_t accTargetLooptime;
uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
static uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
extern uint16_t InflightcalibratingA;
extern bool AccInflightCalibrationArmed;
extern bool AccInflightCalibrationMeasurementDone;
extern bool AccInflightCalibrationSavetoEEProm;
extern bool AccInflightCalibrationActive;
@ -56,7 +54,7 @@ extern bool AccInflightCalibrationActive;
static flightDynamicsTrims_t *accelerationTrims;
static float accLpfCutHz = 0;
static biquad_t accFilterState[XYZ_AXIS_COUNT];
static biquadFilter_t accFilter[XYZ_AXIS_COUNT];
static bool accFilterInitialised = false;
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired)
@ -88,9 +86,8 @@ void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims)
void performAcclerationCalibration(rollAndPitchTrims_t *rollAndPitchTrims)
{
static int32_t a[3];
int axis;
for (axis = 0; axis < 3; axis++) {
for (int axis = 0; axis < 3; axis++) {
// Reset a[axis] at start of calibration
if (isOnFirstAccelerationCalibrationCycle())
@ -181,13 +178,12 @@ void applyAccelerationTrims(flightDynamicsTrims_t *accelerationTrims)
void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
{
int16_t accADCRaw[XYZ_AXIS_COUNT];
int axis;
if (!acc.read(accADCRaw)) {
return;
}
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
if (debugMode == DEBUG_ACCELEROMETER) debug[axis] = accADCRaw[axis];
accSmooth[axis] = accADCRaw[axis];
}
@ -195,13 +191,17 @@ void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
if (accLpfCutHz) {
if (!accFilterInitialised) {
if (accTargetLooptime) { /* Initialisation needs to happen once sample rate is known */
for (axis = 0; axis < 3; axis++) BiQuadNewLpf(accLpfCutHz, &accFilterState[axis], accTargetLooptime);
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInit(&accFilter[axis], accLpfCutHz, accTargetLooptime);
}
accFilterInitialised = true;
}
}
if (accFilterInitialised) {
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) accSmooth[axis] = lrintf(applyBiQuadFilter((float) accSmooth[axis], &accFilterState[axis]));
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
accSmooth[axis] = lrintf(biquadFilterApply(&accFilter[axis], (float)accSmooth[axis]));
}
}
}

View File

@ -29,10 +29,9 @@ typedef enum {
ACC_MPU6000 = 7,
ACC_MPU6500 = 8,
ACC_FAKE = 9,
ACC_MAX = ACC_FAKE
} accelerationSensor_e;
#define ACC_MAX ACC_FAKE
extern sensor_align_e accAlign;
extern acc_t acc;
extern uint32_t accTargetLooptime;

View File

@ -20,6 +20,10 @@
#include <math.h>
#include "platform.h"
int32_t BaroAlt = 0;
#ifdef BARO
#include "common/maths.h"
#include "drivers/barometer.h"
@ -32,9 +36,6 @@ baro_t baro; // barometer access functions
uint16_t calibratingB = 0; // baro calibration = get new ground pressure value
int32_t baroPressure = 0;
int32_t baroTemperature = 0;
int32_t BaroAlt = 0;
#ifdef BARO
static int32_t baroGroundAltitude = 0;
static int32_t baroGroundPressure = 0;

View File

@ -22,11 +22,11 @@ typedef enum {
BARO_NONE = 1,
BARO_BMP085 = 2,
BARO_MS5611 = 3,
BARO_BMP280 = 4
BARO_BMP280 = 4,
BARO_MAX = BARO_BMP280
} baroSensor_e;
#define BARO_SAMPLE_COUNT_MAX 48
#define BARO_MAX BARO_MS5611
typedef struct barometerConfig_s {
uint8_t baro_sample_count; // size of baro filter array
@ -38,7 +38,6 @@ typedef struct barometerConfig_s {
extern int32_t BaroAlt;
extern int32_t baroTemperature; // Use temperature for telemetry
#ifdef BARO
void useBarometerConfig(barometerConfig_t *barometerConfigToUse);
bool isBaroCalibrationComplete(void);
void baroSetCalibrationCycles(uint16_t calibrationCyclesRequired);
@ -46,4 +45,3 @@ uint32_t baroUpdate(void);
bool isBaroReady(void);
int32_t baroCalculateAltitude(void);
void performBaroCalibrationCycle(void);
#endif

View File

@ -63,20 +63,19 @@ uint16_t batteryAdcToVoltage(uint16_t src)
static void updateBatteryVoltage(void)
{
uint16_t vbatSample;
static biquad_t vbatFilterState;
static bool vbatFilterStateIsSet;
static biquadFilter_t vbatFilter;
static bool vbatFilterIsInitialised;
// store the battery voltage with some other recent battery voltage readings
vbatSample = vbatLatestADC = adcGetChannel(ADC_BATTERY);
uint16_t vbatSample = vbatLatestADC = adcGetChannel(ADC_BATTERY);
if (debugMode == DEBUG_BATTERY) debug[0] = vbatSample;
if (!vbatFilterStateIsSet) {
BiQuadNewLpf(VBATT_LPF_FREQ, &vbatFilterState, 50000); //50HZ Update
vbatFilterStateIsSet = true;
if (!vbatFilterIsInitialised) {
biquadFilterInit(&vbatFilter, VBATT_LPF_FREQ, 50000); //50HZ Update
vbatFilterIsInitialised = true;
}
vbatSample = applyBiQuadFilter(vbatSample, &vbatFilterState);
vbatSample = biquadFilterApply(&vbatFilter, vbatSample);
vbat = batteryAdcToVoltage(vbatSample);
if (debugMode == DEBUG_BATTERY) debug[1] = vbat;

View File

@ -20,7 +20,9 @@
#include "rx/rx.h"
#include "common/maths.h"
#ifndef VBAT_SCALE_DEFAULT
#define VBAT_SCALE_DEFAULT 110
#endif
#define VBAT_RESDIVVAL_DEFAULT 10
#define VBAT_RESDIVMULTIPLIER_DEFAULT 1
#define VBAT_SCALE_MIN 0

View File

@ -35,18 +35,19 @@
#include "sensors/sensors.h"
#include "sensors/compass.h"
#ifdef NAZE
#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
#endif
mag_t mag; // mag access functions
int32_t magADC[XYZ_AXIS_COUNT];
sensor_align_e magAlign = 0;
#ifdef MAG
extern uint32_t currentTime; // FIXME dependency on global variable, pass it in instead.
int16_t magADCRaw[XYZ_AXIS_COUNT];
int32_t magADC[XYZ_AXIS_COUNT];
sensor_align_e magAlign = 0;
#ifdef MAG
static int16_t magADCRaw[XYZ_AXIS_COUNT];
static uint8_t magInit = 0;
void compassInit(void)

View File

@ -23,15 +23,13 @@ typedef enum {
MAG_NONE = 1,
MAG_HMC5883 = 2,
MAG_AK8975 = 3,
MAG_AK8963 = 4
MAG_AK8963 = 4,
MAG_MAX = MAG_AK8963
} magSensor_e;
#define MAG_MAX MAG_AK8963
#ifdef MAG
void compassInit(void);
void updateCompass(flightDynamicsTrims_t *magZero);
#endif
union flightDynamicsTrims_u;
void updateCompass(union flightDynamicsTrims_u *magZero);
extern int32_t magADC[XYZ_AXIS_COUNT];

View File

@ -28,7 +28,6 @@
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/gyro_sync.h"
#include "sensors/sensors.h"
#include "io/beeper.h"
#include "io/statusindicator.h"
@ -36,36 +35,31 @@
#include "sensors/gyro.h"
uint16_t calibratingG = 0;
int32_t gyroADC[XYZ_AXIS_COUNT];
float gyroADCf[XYZ_AXIS_COUNT];
int32_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT] = { 0, 0, 0 };
static gyroConfig_t *gyroConfig;
static biquad_t gyroFilterState[3];
static bool gyroFilterStateIsSet;
static float gyroLpfCutFreq;
gyro_t gyro; // gyro access functions
sensor_align_e gyroAlign = 0;
void useGyroConfig(gyroConfig_t *gyroConfigToUse, float gyro_lpf_hz)
int32_t gyroADC[XYZ_AXIS_COUNT];
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 uint8_t gyroSoftLpfHz;
static uint16_t calibratingG = 0;
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz)
{
gyroConfig = gyroConfigToUse;
gyroLpfCutFreq = gyro_lpf_hz;
gyroSoftLpfHz = gyro_soft_lpf_hz;
}
void initGyroFilterCoefficients(void) {
int axis;
if (gyroLpfCutFreq && targetLooptime) { /* Initialisation needs to happen once samplingrate is known */
for (axis = 0; axis < 3; axis++) BiQuadNewLpf(gyroLpfCutFreq, &gyroFilterState[axis], targetLooptime);
gyroFilterStateIsSet = true;
}
}
void gyroSetCalibrationCycles(uint16_t calibrationCyclesRequired)
void gyroInit(void)
{
calibratingG = calibrationCyclesRequired;
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);
}
}
}
bool isGyroCalibrationComplete(void)
@ -73,27 +67,32 @@ bool isGyroCalibrationComplete(void)
return calibratingG == 0;
}
bool isOnFinalGyroCalibrationCycle(void)
static bool isOnFinalGyroCalibrationCycle(void)
{
return calibratingG == 1;
}
uint16_t calculateCalibratingCycles(void) {
return (CALIBRATING_GYRO_CYCLES / targetLooptime) * CALIBRATING_GYRO_CYCLES;
static uint16_t gyroCalculateCalibratingCycles(void)
{
return (CALIBRATING_GYRO_CYCLES / gyro.targetLooptime) * CALIBRATING_GYRO_CYCLES;
}
bool isOnFirstGyroCalibrationCycle(void)
static bool isOnFirstGyroCalibrationCycle(void)
{
return calibratingG == calculateCalibratingCycles();
return calibratingG == gyroCalculateCalibratingCycles();
}
void gyroSetCalibrationCycles(void)
{
calibratingG = gyroCalculateCalibratingCycles();
}
static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThreshold)
{
int8_t axis;
static int32_t g[3];
static stdev_t var[3];
for (axis = 0; axis < 3; axis++) {
for (int axis = 0; axis < 3; axis++) {
// Reset g[axis] at start of calibration
if (isOnFirstGyroCalibrationCycle()) {
@ -113,10 +112,10 @@ static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThresho
float dev = devStandardDeviation(&var[axis]);
// check deviation and startover in case the model was moved
if (gyroMovementCalibrationThreshold && dev > gyroMovementCalibrationThreshold) {
gyroSetCalibrationCycles(calculateCalibratingCycles());
gyroSetCalibrationCycles();
return;
}
gyroZero[axis] = (g[axis] + (calculateCalibratingCycles() / 2)) / calculateCalibratingCycles();
gyroZero[axis] = (g[axis] + (gyroCalculateCalibratingCycles() / 2)) / gyroCalculateCalibratingCycles();
}
}
@ -129,8 +128,7 @@ static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThresho
static void applyGyroZero(void)
{
int8_t axis;
for (axis = 0; axis < 3; axis++) {
for (int axis = 0; axis < 3; axis++) {
gyroADC[axis] -= gyroZero[axis];
}
}
@ -138,14 +136,13 @@ static void applyGyroZero(void)
void gyroUpdate(void)
{
int16_t gyroADCRaw[XYZ_AXIS_COUNT];
int axis;
// range: +/- 8192; +/- 2000 deg/sec
if (!gyro.read(gyroADCRaw)) {
return;
}
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
if (debugMode == DEBUG_GYRO) debug[axis] = gyroADC[axis];
gyroADC[axis] = gyroADCRaw[axis];
}
@ -158,16 +155,14 @@ void gyroUpdate(void)
applyGyroZero();
if (gyroLpfCutFreq) {
if (!gyroFilterStateIsSet) initGyroFilterCoefficients(); /* initialise filter coefficients */
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
if (gyroFilterStateIsSet) {
gyroADCf[axis] = applyBiQuadFilter((float) gyroADC[axis], &gyroFilterState[axis]);
if (gyroSoftLpfHz) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
gyroADCf[axis] = biquadFilterApply(&gyroFilter[axis], (float)gyroADC[axis]);
gyroADC[axis] = lrintf(gyroADCf[axis]);
} else {
gyroADCf[axis] = gyroADC[axis]; // Otherwise float pid controller will not have gyro input when filter disabled
}
} else {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
gyroADCf[axis] = gyroADC[axis];
}
}
}

View File

@ -27,23 +27,22 @@ typedef enum {
GYRO_MPU6000,
GYRO_MPU6500,
GYRO_MPU9250,
GYRO_FAKE
GYRO_FAKE,
GYRO_MAX = GYRO_FAKE
} gyroSensor_e;
extern gyro_t gyro;
extern sensor_align_e gyroAlign;
extern int32_t gyroADC[XYZ_AXIS_COUNT];
extern float gyroADCf[XYZ_AXIS_COUNT];
extern int32_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT];
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 useGyroConfig(gyroConfig_t *gyroConfigToUse, float gyro_lpf_hz);
void gyroSetCalibrationCycles(uint16_t calibrationCyclesRequired);
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_lpf_hz);
void gyroSetCalibrationCycles(void);
void gyroInit(void);
void gyroUpdate(void);
bool isGyroCalibrationComplete(void);
uint16_t calculateCalibratingCycles(void);

View File

@ -79,8 +79,9 @@ extern float magneticDeclination;
extern gyro_t gyro;
extern baro_t baro;
extern acc_t acc;
extern sensor_align_e gyroAlign;
uint8_t detectedSensors[MAX_SENSORS_TO_DETECT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE };
uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE };
const extiConfig_t *selectMPUIntExtiConfig(void)
@ -483,27 +484,12 @@ static void detectMag(magSensor_e magHardwareToUse)
#ifdef USE_MAG_HMC5883
const hmc5883Config_t *hmc5883Config = 0;
#ifdef NAZE
#ifdef NAZE // TODO remove this target specific define
static const hmc5883Config_t nazeHmc5883Config_v1_v4 = {
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOB,
.gpioPin = Pin_12,
.gpioPort = GPIOB,
/* Disabled for v4 needs more work.
.exti_port_source = GPIO_PortSourceGPIOB,
.exti_pin_source = GPIO_PinSource12,
.exti_line = EXTI_Line12,
.exti_irqn = EXTI15_10_IRQn
*/
.intTag = IO_TAG(PB12) /* perhaps disabled? */
};
static const hmc5883Config_t nazeHmc5883Config_v5 = {
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOC,
.gpioPin = Pin_14,
.gpioPort = GPIOC,
.exti_port_source = GPIO_PortSourceGPIOC,
.exti_line = EXTI_Line14,
.exti_pin_source = GPIO_PinSource14,
.exti_irqn = EXTI15_10_IRQn
.intTag = IO_TAG(MAG_INT_EXTI)
};
if (hardwareRevision < NAZE32_REV5) {
hmc5883Config = &nazeHmc5883Config_v1_v4;
@ -512,18 +498,12 @@ static void detectMag(magSensor_e magHardwareToUse)
}
#endif
#ifdef SPRACINGF3
static const hmc5883Config_t spRacingF3Hmc5883Config = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
.gpioPin = Pin_14,
.gpioPort = GPIOC,
.exti_port_source = EXTI_PortSourceGPIOC,
.exti_pin_source = EXTI_PinSource14,
.exti_line = EXTI_Line14,
.exti_irqn = EXTI15_10_IRQn
#ifdef MAG_INT_EXTI
static const hmc5883Config_t extiHmc5883Config = {
.intTag = IO_TAG(MAG_INT_EXTI)
};
hmc5883Config = &spRacingF3Hmc5883Config;
hmc5883Config = &extiHmc5883Config;
#endif
#endif
@ -632,8 +612,9 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t a
acc.init(&acc);
}
// this is safe because either mpu6050 or mpu3050 or lg3d20 sets it, and in case of fail, we never get here.
gyroUpdateSampleRate(gyroLpf, gyroSyncDenominator); // Set gyro refresh rate before initialisation
gyro.targetLooptime = gyroSetSampleRate(gyroLpf, gyroSyncDenominator); // Set gyro sample rate before initialisation
gyro.init(gyroLpf);
gyroInit();
detectMag(magHardwareToUse);

View File

@ -21,12 +21,11 @@ typedef enum {
SENSOR_INDEX_GYRO = 0,
SENSOR_INDEX_ACC,
SENSOR_INDEX_BARO,
SENSOR_INDEX_MAG
SENSOR_INDEX_MAG,
SENSOR_INDEX_COUNT
} sensorIndex_e;
#define MAX_SENSORS_TO_DETECT (SENSOR_INDEX_MAG + 1)
extern uint8_t detectedSensors[MAX_SENSORS_TO_DETECT];
extern uint8_t detectedSensors[SENSOR_INDEX_COUNT];
typedef struct int16_flightDynamicsTrims_s {
int16_t roll;
@ -34,7 +33,7 @@ typedef struct int16_flightDynamicsTrims_s {
int16_t yaw;
} flightDynamicsTrims_def_t;
typedef union {
typedef union flightDynamicsTrims_u {
int16_t raw[3];
flightDynamicsTrims_def_t values;
} flightDynamicsTrims_t;

View File

@ -0,0 +1,100 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void) {
featureClear(FEATURE_ONESHOT125);
masterConfig.mag_hardware = MAG_NONE; // disabled by default
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
currentControlRateProfile->rates[FD_PITCH] = 40;
currentControlRateProfile->rates[FD_ROLL] = 40;
currentControlRateProfile->rates[FD_YAW] = 40;
parseRcChannels("TAER1234", &masterConfig.rxConfig);
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
}

View File

@ -1,5 +1,20 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
@ -48,37 +63,28 @@ const uint16_t airPWM[] = {
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
//
// 6 x 3 pin headers
//
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
//
// 6 pin header
//
// PWM7-10
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM9 - PA4 - *TIM3_CH2
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
//
// PPM PORT - Also USART2 RX (AF5)
//
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, GPIO_AF_1, 0} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
//{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_IPD, GPIO_PinSource3, GPIO_AF_9, 0} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
//{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_IPD, GPIO_PinSource3, GPIO_AF_9 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
// USART3 RX/TX
// RX conflicts with PPM port
//{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1, 0} // RX - PB11 - *TIM2_CH4, USART3_RX (AF7) - PWM11
//{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1, 0} // TX - PB10 - *TIM2_CH3, USART3_TX (AF7) - PWM12
//{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1 } // RX - PB11 - *TIM2_CH4, USART3_RX (AF7) - PWM11
//{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1 } // TX - PB10 - *TIM2_CH3, USART3_TX (AF7) - PWM12
};

View File

@ -18,6 +18,7 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
#define TARGET_CONFIG
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
@ -116,11 +117,8 @@
#define USE_ADC
#define ADC_INSTANCE ADC2
//#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PA4
// alternative defaults for AlienFlight F3 target
#define ALIENFLIGHT
#define VBAT_SCALE_DEFAULT 20
#define SPEKTRUM_BIND
// USART2, PA3
@ -131,8 +129,10 @@
#define BINDPLUG_PIN PB12
#define BRUSHED_MOTORS
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
#define SERIALRX_UART SERIAL_PORT_USART3
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -0,0 +1,100 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void) {
featureClear(FEATURE_ONESHOT125);
masterConfig.mag_hardware = MAG_NONE; // disabled by default
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
currentControlRateProfile->rates[FD_PITCH] = 40;
currentControlRateProfile->rates[FD_ROLL] = 40;
currentControlRateProfile->rates[FD_YAW] = 40;
parseRcChannels("TAER1234", &masterConfig.rxConfig);
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
}

View File

@ -1,5 +1,22 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdbool.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
@ -73,19 +90,19 @@ const uint16_t airPWM[] = {
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // PWM1 - PA8 RC1
{ TIM1, IO_TAG(PB0), TIM_Channel_2, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // PWM2 - PB0 RC2
{ TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // PWM3 - PB1 RC3
{ TIM8, IO_TAG(PB14),TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PWM4 - PA14 RC4
{ TIM8, IO_TAG(PB15),TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PWM5 - PA15 RC5
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PWM1 - PA8 RC1
{ TIM1, IO_TAG(PB0), TIM_Channel_2, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PWM2 - PB0 RC2
{ TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PWM3 - PB1 RC3
{ TIM8, IO_TAG(PB14),TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PWM4 - PA14 RC4
{ TIM8, IO_TAG(PB15),TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PWM5 - PA15 RC5
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4, 0}, // PWM6 - PB8 OUT1
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4, 0}, // PWM7 - PB9 OUT2
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0}, // PWM8 - PA0 OUT3
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0}, // PWM9 - PA1 OUT4
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // PWM10 - PC6 OUT5
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // PWM11 - PC7 OUT6
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // PWM13 - PC8 OUT7
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // PWM13 - PC9 OUT8
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // PWM6 - PB8 OUT1
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // PWM7 - PB9 OUT2
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // PWM8 - PA0 OUT3
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // PWM9 - PA1 OUT4
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM10 - PC6 OUT5
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM11 - PC7 OUT6
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM13 - PC8 OUT7
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM13 - PC9 OUT8
};

View File

@ -17,6 +17,7 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFF4"
#define TARGET_CONFIG
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
@ -146,22 +147,13 @@
// LED strip configuration using RC5 pin.
//#define LED_STRIP
//#define LED_STRIP_TIMER TIM8
//#define USE_LED_STRIP_ON_DMA1_CHANNEL3
//#define WS2811_GPIO GPIOB
//#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB
//#define WS2811_GPIO_AF GPIO_AF_3
//#define WS2811_PIN GPIO_Pin_15 // TIM8_CH3
//#define WS2811_PIN_SOURCE GPIO_PinSource15
//#define WS2811_PIN PB15 // TIM8_CH3
//#define WS2811_TIMER TIM8
//#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM8
//#define WS2811_DMA_CHANNEL DMA1_Channel3
//#define WS2811_IRQ DMA1_Channel3_IRQn
// alternative defaults for AlienFlight F4 target
#define ALIENFLIGHT
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3
@ -173,8 +165,10 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define BRUSHED_MOTORS
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES (FEATURE_MOTOR_STOP | FEATURE_BLACKBOX)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
#define SERIALRX_UART SERIAL_PORT_USART3
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -1,5 +1,20 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
@ -51,12 +66,12 @@ const uint16_t airPWM[] = {
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM8, 0 }, // PPM IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0 }, // S1_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0 }, // S2_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, 0 }, // S3_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9, 0 }, // S4_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0 }, // S5_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0 }, // S6_OUT
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM8 }, // PPM IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S1_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S2_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S3_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S4_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S6_OUT
};

View File

@ -134,6 +134,19 @@
#define USE_ADC
#define VBAT_ADC_PIN PC3
#define LED_STRIP
// LED Strip can run off Pin 6 (PB1) of the ESC outputs.
#define WS2811_PIN PB1
#define WS2811_TIMER TIM3
#define WS2811_TIMER_CHANNEL TIM_Channel_4
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER
#define WS2811_DMA_STREAM DMA1_Stream2
#define WS2811_DMA_FLAG DMA_FLAG_TCIF2
#define WS2811_DMA_IT DMA_IT_TCIF2
#define WS2811_DMA_CHANNEL DMA_Channel_5
#define WS2811_DMA_IRQ DMA1_Stream2_IRQn
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM

View File

@ -4,5 +4,7 @@ FEATURES += SDCARD VCP
TARGET_SRC = \
drivers/accgyro_spi_mpu6500.c \
drivers/accgyro_mpu6500.c \
drivers/barometer_ms5611.c
drivers/barometer_ms5611.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f4xx.c

View File

@ -1,5 +1,20 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
@ -128,17 +143,17 @@ const uint16_t airPWM_BP6[] = {
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // S1_IN
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // S4_IN - Current
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // S5_IN - Vbattery
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // S6_IN - PPM IN
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, 0}, // S1_OUT
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, 0}, // S2_OUT
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, 0}, // S3_OUT
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, 0}, // S4_OUT
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, 0}, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, 0} // S6_OUT
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // S1_IN
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // S4_IN - Current
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // S5_IN - Vbattery
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // S6_IN - PPM IN
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP }, // S1_OUT
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP }, // S2_OUT
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP }, // S3_OUT
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP }, // S4_OUT
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP }, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP } // S6_OUT
};

View File

@ -97,7 +97,8 @@
#define RSSI_ADC_PIN PB0
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
#define WS2811_PIN PB4
#define WS2811_TIMER TIM3
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER

View File

@ -1,8 +1,24 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
@ -73,23 +89,23 @@ const uint16_t airPWM[] = {
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// INPUTS CH1-8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM2 - PB8
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM3 - PB9
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM4 - PC6
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM5 - PC7
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM6 - PC8
{ TIM15, IO_TAG(PF9), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3, 0}, // PWM7 - PF9
{ TIM15, IO_TAG(PF10), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3, 0}, // PWM8 - PF10
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM9 - PD12
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM10 - PD13
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM11 - PD14
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM12 - PD15
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM13 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM14 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM15 - PA3
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM16 - PB0
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM17 - PB1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0} // PWM18 - PA4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM2 - PB8
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM3 - PB9
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM4 - PC6
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM5 - PC7
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM6 - PC8
{ TIM15, IO_TAG(PF9), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3 }, // PWM7 - PF9
{ TIM15, IO_TAG(PF10), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3 }, // PWM8 - PF10
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PD12
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM10 - PD13
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM11 - PD14
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM12 - PD15
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM13 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM14 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM15 - PA3
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM16 - PB0
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM17 - PB1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 } // PWM18 - PA4
};

View File

@ -1,5 +1,20 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
@ -38,19 +53,19 @@ const uint16_t airPWM[] = {
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0} // PWM14 - OUT6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6
};

View File

@ -0,0 +1,84 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
// alternative defaults settings for COLIBRI RACE targets
void targetConfiguration(void) {
masterConfig.escAndServoConfig.minthrottle = 1025;
masterConfig.escAndServoConfig.maxthrottle = 1980;
masterConfig.batteryConfig.vbatmaxcellvoltage = 45;
masterConfig.batteryConfig.vbatmincellvoltage = 30;
}

View File

@ -1403,7 +1403,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
ledConfig->color = bstRead8();
reevalulateLedConfig();
reevaluateLedConfig();
}
break;
#endif

View File

@ -1,5 +1,20 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
@ -67,16 +82,16 @@ const uint16_t airPWM[] = {
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PC6
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PC7
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PMW4 - PC8
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PC9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM9 - PA3
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM10 - PB14
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM11 - PB15
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PC6
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PC7
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PMW4 - PC8
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PC9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PA3
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM10 - PB14
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM11 - PB15
};

View File

@ -20,6 +20,7 @@
#define TARGET_BOARD_IDENTIFIER "CLBR"
#define BST_DEVICE_NAME "COLIBRI RACE"
#define BST_DEVICE_NAME_LENGTH 12
#define TARGET_CONFIG
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
@ -113,7 +114,6 @@
#define USE_ADC
#define ADC_INSTANCE ADC1
#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PC0
#define CURRENT_METER_ADC_PIN PC1
#define RSSI_ADC_PIN PC2
@ -122,15 +122,8 @@
#define LED_STRIP
#define USE_COLIBTI_RACE_LED_DEFAULT_CONFIG
#define LED_STRIP_TIMER TIM16
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_1
#define WS2811_PIN GPIO_Pin_6 // TIM16_CH1
#define WS2811_PIN_SOURCE GPIO_PinSource6
#define WS2811_PIN PA6 // TIM16_CH1
#define WS2811_TIMER TIM16
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16
#define WS2811_DMA_CHANNEL DMA1_Channel3
#define WS2811_IRQ DMA1_Channel3_IRQn
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3
@ -144,7 +137,10 @@
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES FEATURE_VBAT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART3
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -1,8 +1,24 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
@ -58,17 +74,17 @@ const uint16_t airPWM[] = {
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB9
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB9
{ TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PMW4 - PA10
{ TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM5 - PA9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - PA1
{ TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PMW4 - PA10
{ TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM5 - PA9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PWM8 - PB1
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PWM9 - PB0
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PWM8 - PB1
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PWM9 - PB0
};

View File

@ -140,15 +140,9 @@
#define LED_STRIP
// tqfp48 pin 16
#define LED_STRIP_TIMER TIM16
#define USE_LED_STRIP_ON_DMA1_CHANNEL3
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_1
#define WS2811_PIN GPIO_Pin_6 // TIM16_CH1
#define WS2811_PIN_SOURCE GPIO_PinSource6
#define WS2811_PIN PA6 // TIM16_CH1
#define WS2811_TIMER TIM16
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16
#define WS2811_DMA_CHANNEL DMA1_Channel3
#define WS2811_IRQ DMA1_Channel3_IRQn
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3

View File

@ -1,8 +1,24 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
@ -72,19 +88,19 @@ const uint16_t airPWM[] = {
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0 }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0 } // PWM14 - OUT6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6
};

View File

@ -102,9 +102,6 @@
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA5
//#define LED_STRIP
#define LED_STRIP_TIMER TIM3
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3

View File

@ -1,8 +1,24 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
@ -52,15 +68,15 @@ const uint16_t airPWM[] = {
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PPM IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PPM IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - S1
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - S2
{ TIM17, IO_TAG(PB5), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM6 - S3
{ TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - S4
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - S1
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - S2
{ TIM17, IO_TAG(PB5), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10}, // PWM6 - S3
{ TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - S4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO TIMER - LED_STRIP
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO TIMER - LED_STRIP
};

View File

@ -156,16 +156,10 @@
#define CURRENT_METER_ADC_PIN PA2
#define LED_STRIP
#define LED_STRIP_TIMER TIM1
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_6
#define WS2811_PIN GPIO_Pin_8
#define WS2811_PIN_SOURCE GPIO_PinSource8
#define WS2811_PIN PA8
#define WS2811_TIMER TIM1
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
#define WS2811_DMA_CHANNEL DMA1_Channel2
#define WS2811_IRQ DMA1_Channel2_IRQn
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
@ -175,8 +169,8 @@
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB0
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define SPEKTRUM_BIND
// USART3,

View File

@ -1,8 +1,24 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
@ -42,13 +58,13 @@ const uint16_t airPWM[] = {
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PPM_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PPM_IN
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9, 0}, // S1_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, 0}, // S4_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S1_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S4_OUT
// { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5, 0}, // LED Strip
// { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5 }, // LED Strip
};

Some files were not shown because too many files have changed in this diff Show More