mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +03:00
merge upstream into sirinfpv branch
This commit is contained in:
commit
eb5963809d
77 changed files with 3017 additions and 946 deletions
|
@ -26,7 +26,6 @@
|
|||
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/atomic.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "drivers/nvic.h"
|
||||
|
@ -45,6 +44,7 @@
|
|||
#include "drivers/compass.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/bus_bst.h"
|
||||
|
@ -71,6 +71,7 @@
|
|||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
#include "io/transponder_ir.h"
|
||||
#include "io/osd.h"
|
||||
#include "io/vtx.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/sonar.h"
|
||||
|
@ -179,7 +180,7 @@ void init(void)
|
|||
#ifdef STM32F10X
|
||||
// Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers
|
||||
// Configure the Flash Latency cycles and enable prefetch buffer
|
||||
SetSysClock(masterConfig.emf_avoidance);
|
||||
SetSysClock(0); // TODO - Remove from config in the future
|
||||
#endif
|
||||
//i2cSetOverclock(masterConfig.i2c_overclock);
|
||||
|
||||
|
@ -314,18 +315,20 @@ void init(void)
|
|||
pwm_params.servoPwmRate = masterConfig.servo_pwm_rate;
|
||||
#endif
|
||||
|
||||
pwm_params.useOneshot = feature(FEATURE_ONESHOT125);
|
||||
if (masterConfig.use_oneshot42) {
|
||||
pwm_params.useOneshot42 = masterConfig.use_oneshot42 ? true : false;
|
||||
masterConfig.use_multiShot = false;
|
||||
if (masterConfig.fast_pwm_protocol == PWM_TYPE_ONESHOT125) {
|
||||
featureSet(FEATURE_ONESHOT125);
|
||||
} else {
|
||||
pwm_params.useMultiShot = masterConfig.use_multiShot ? true : false;
|
||||
featureClear(FEATURE_ONESHOT125);
|
||||
}
|
||||
|
||||
pwm_params.useFastPwm = (masterConfig.fast_pwm_protocol != PWM_TYPE_CONVENTIONAL) ? true : false; // Configurator feature abused for enabling Fast PWM
|
||||
pwm_params.pwmProtocolType = masterConfig.fast_pwm_protocol;
|
||||
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
|
||||
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;
|
||||
pwm_params.useUnsyncedPwm = masterConfig.use_unsyncedPwm;
|
||||
if (feature(FEATURE_3D))
|
||||
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
|
||||
if (pwm_params.motorPwmRate > 500)
|
||||
if (pwm_params.motorPwmRate > 500 && !pwm_params.useFastPwm)
|
||||
pwm_params.idlePulse = 0; // brushed motors
|
||||
#ifdef CC3D
|
||||
pwm_params.useBuzzerP6 = masterConfig.use_buzzer_p6 ? true : false;
|
||||
|
@ -397,6 +400,10 @@ void init(void)
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef VTX
|
||||
vtxInit();
|
||||
#endif
|
||||
|
||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||
updateHardwareRevision();
|
||||
#endif
|
||||
|
@ -421,6 +428,11 @@ void init(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(FURYF3) && defined(SONAR) && defined(USE_SOFTSERIAL1)
|
||||
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
||||
serialRemovePort(SERIAL_PORT_SOFTSERIAL1);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_I2C
|
||||
#if defined(NAZE)
|
||||
|
@ -486,7 +498,7 @@ void init(void)
|
|||
LED1_TOGGLE;
|
||||
LED0_TOGGLE;
|
||||
delay(25);
|
||||
if (!(getPreferedBeeperOffMask() & (1 << (BEEPER_SYSTEM_INIT - 1)))) BEEP_ON;
|
||||
if (!(getBeeperOffMask() & (1 << (BEEPER_SYSTEM_INIT - 1)))) BEEP_ON;
|
||||
delay(25);
|
||||
BEEP_OFF;
|
||||
}
|
||||
|
@ -666,7 +678,7 @@ void processLoopback(void) {
|
|||
#define processLoopback()
|
||||
#endif
|
||||
|
||||
int main(void) {
|
||||
void main_init(void) {
|
||||
init();
|
||||
|
||||
/* Setup scheduler */
|
||||
|
@ -740,12 +752,24 @@ int main(void) {
|
|||
#ifdef USE_BST
|
||||
setTaskEnabled(TASK_BST_MASTER_PROCESS, true);
|
||||
#endif
|
||||
}
|
||||
|
||||
while (1) {
|
||||
scheduler();
|
||||
processLoopback();
|
||||
void main_step(void)
|
||||
{
|
||||
scheduler();
|
||||
processLoopback();
|
||||
}
|
||||
|
||||
#ifndef NOMAIN
|
||||
int main(void)
|
||||
{
|
||||
main_init();
|
||||
while(1) {
|
||||
main_step();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef DEBUG_HARDFAULTS
|
||||
//from: https://mcuoneclipse.com/2012/11/24/debugging-hard-faults-on-arm-cortex-m/
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue