Merge branch 'master' into development

This commit is contained in:
borisbstyle 2016-10-07 01:41:55 +02:00
commit 09d16bd0cb
28 changed files with 482 additions and 145 deletions

View File

@ -87,6 +87,7 @@ cache: apt
# skip_join: true
notifications:
slack: betaflightgroup:LQSj02nsBEdefcO5UQcLgB0U
webhooks:
urls:
- https://webhooks.gitter.im/e/0c20f7a1a7e311499a88

View File

@ -1231,10 +1231,10 @@ static bool blackboxWriteSysinfo()
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDVEL],
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDVEL]);
BLACKBOX_PRINT_HEADER_LINE("dterm_filter_type:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_filter_type);
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_notch_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_notch_cutoff * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_notch_hz);
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_notch_cutoff);
BLACKBOX_PRINT_HEADER_LINE("deltaMethod:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.deltaMethod);
BLACKBOX_PRINT_HEADER_LINE("rollPitchItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate);
BLACKBOX_PRINT_HEADER_LINE("yawItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate);
@ -1245,7 +1245,7 @@ static bool blackboxWriteSysinfo()
// Betaflight PID controller parameters
BLACKBOX_PRINT_HEADER_LINE("itermThrottleGain:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.itermThrottleGain);
BLACKBOX_PRINT_HEADER_LINE("ptermSRateWeight:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.ptermSRateWeight);
BLACKBOX_PRINT_HEADER_LINE("setpointRelaxRatio:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.setpointRelaxRatio);
BLACKBOX_PRINT_HEADER_LINE("dtermSetpointWeight:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dtermSetpointWeight);
BLACKBOX_PRINT_HEADER_LINE("yawRateAccelLimit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawRateAccelLimit);
BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rateAccelLimit);
@ -1255,9 +1255,11 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband);
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", masterConfig.gyro_lpf);
BLACKBOX_PRINT_HEADER_LINE("gyro_soft_type:%d", masterConfig.gyro_soft_type);
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz:%d", (int)(masterConfig.gyro_soft_notch_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff:%d", (int)(masterConfig.gyro_soft_notch_cutoff * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", masterConfig.gyro_soft_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz:%d,%d", masterConfig.gyro_soft_notch_hz_1,
masterConfig.gyro_soft_notch_hz_2);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff:%d,%d", masterConfig.gyro_soft_notch_cutoff_1,
masterConfig.gyro_soft_notch_cutoff_2);
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.acc_hardware);
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.baro_hardware);

View File

@ -107,7 +107,7 @@ void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refresh
filter->d1 = filter->d2 = 0;
}
/* Computes a biquad_t filter on a sample */
/* Computes a biquadFilter_t filter on a sample */
float biquadFilterApply(biquadFilter_t *filter, float input)
{
const float result = filter->b0 * input + filter->d1;

View File

@ -141,10 +141,10 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->P8[ROLL] = 45;
pidProfile->I8[ROLL] = 40;
pidProfile->D8[ROLL] = 20;
pidProfile->D8[ROLL] = 16;
pidProfile->P8[PITCH] = 60;
pidProfile->I8[PITCH] = 65;
pidProfile->D8[PITCH] = 22;
pidProfile->D8[PITCH] = 19;
pidProfile->P8[YAW] = 70;
pidProfile->I8[YAW] = 45;
pidProfile->D8[YAW] = 20;
@ -181,8 +181,8 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
// Betaflight PID controller parameters
pidProfile->ptermSRateWeight = 85;
pidProfile->dtermSetpointWeight = 150;
pidProfile->setpointRelaxRatio = 70;
pidProfile->dtermSetpointWeight = 200;
pidProfile->yawRateAccelLimit = 220;
pidProfile->rateAccelLimit = 0;
pidProfile->itermThrottleGain = 0;
@ -432,9 +432,11 @@ void createDefaultConfig(master_t *config)
config->pid_process_denom = 2;
#endif
config->gyro_soft_type = FILTER_PT1;
config->gyro_soft_lpf_hz = 90;
config->gyro_soft_notch_hz = 0;
config->gyro_soft_notch_cutoff = 130;
config->gyro_soft_lpf_hz = 80;
config->gyro_soft_notch_hz_1 = 400;
config->gyro_soft_notch_cutoff_1 = 300;
config->gyro_soft_notch_hz_2 = 0;
config->gyro_soft_notch_cutoff_2 = 100;
config->debug_mode = DEBUG_NONE;
@ -668,7 +670,20 @@ void activateConfig(void)
&currentProfile->pidProfile
);
gyroUseConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz, masterConfig.gyro_soft_notch_hz, masterConfig.gyro_soft_notch_cutoff, masterConfig.gyro_soft_type);
// Prevent invalid notch cutoff
if (masterConfig.gyro_soft_notch_cutoff_1 >= masterConfig.gyro_soft_notch_hz_1)
masterConfig.gyro_soft_notch_hz_1 = 0;
if (masterConfig.gyro_soft_notch_cutoff_2 >= masterConfig.gyro_soft_notch_hz_2)
masterConfig.gyro_soft_notch_hz_2 = 0;
gyroUseConfig(&masterConfig.gyroConfig,
masterConfig.gyro_soft_lpf_hz,
masterConfig.gyro_soft_notch_hz_1,
masterConfig.gyro_soft_notch_cutoff_1,
masterConfig.gyro_soft_notch_hz_2,
masterConfig.gyro_soft_notch_cutoff_2,
masterConfig.gyro_soft_type);
#ifdef TELEMETRY
telemetryUseConfig(&masterConfig.telemetryConfig);

View File

@ -100,8 +100,10 @@ typedef struct master_s {
uint8_t gyro_sync_denom; // Gyro sample divider
uint8_t gyro_soft_type; // Gyro Filter Type
uint8_t gyro_soft_lpf_hz; // Biquad gyro lpf hz
uint16_t gyro_soft_notch_hz; // Biquad gyro notch hz
uint16_t gyro_soft_notch_cutoff; // Biquad gyro notch low cutoff
uint16_t gyro_soft_notch_hz_1; // Biquad gyro notch hz
uint16_t gyro_soft_notch_cutoff_1; // Biquad gyro notch low cutoff
uint16_t gyro_soft_notch_hz_2; // Biquad gyro notch hz
uint16_t gyro_soft_notch_cutoff_2; // Biquad gyro notch low cutoff
uint16_t dcm_kp; // DCM filter proportional gain ( x 10000)
uint16_t dcm_ki; // DCM filter integral gain ( x 10000)

View File

@ -231,6 +231,23 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
type = MAP_TO_SERVO_OUTPUT;
#endif
#if defined(X_RACERSPI)
// skip UART2 ports when necessary
if (init->useUART2) {
// this board maps UART2 and PWM13,PWM14 to the same pins
if (timerIndex == PWM13 || timerIndex == PWM14)
continue;
// remap PWM5+6 as servos when using UART2 .. except if softserial1, but that's caught above
if ((timerIndex == PWM5 || timerIndex == PWM6) && timerHardwarePtr->tim == TIM3)
type = MAP_TO_SERVO_OUTPUT;
} else {
// remap PWM13+14 as servos
if ((timerIndex == PWM13 || timerIndex == PWM14) && timerHardwarePtr->tim == TIM15)
type = MAP_TO_SERVO_OUTPUT;
}
#endif
#if defined(SPRACINGF3MINI) || defined(OMNIBUS)
// remap PWM6+7 as servos
if ((timerIndex == PWM6 || timerIndex == PWM7) && timerHardwarePtr->tim == TIM15)
@ -288,7 +305,12 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
// remap PWM5..8 as servos when used in extended servo mode
if (timerIndex >= PWM5 && timerIndex <= PWM8)
type = MAP_TO_SERVO_OUTPUT;
#elif defined(X_RACERSPI)
// remap PWM3..6 as servos when used in extended servo mode
if (timerIndex >= PWM3 && timerIndex <= PWM6)
type = MAP_TO_SERVO_OUTPUT;
#endif
}
#endif // USE_SERVOS

View File

@ -122,10 +122,9 @@ static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the m
extern uint8_t PIDweight[3];
uint16_t filteredCycleTime;
static bool isRXDataNew;
static bool armingCalibrationWasInitialised;
float setpointRate[3], ptermSetpointRate[3];
float setpointRate[3];
float rcInput[3];
extern pidControllerFuncPtr pid_controller;
@ -203,20 +202,8 @@ void calculateSetpointRate(int axis, int16_t rc) {
if (currentControlRateProfile->rates[axis]) {
rcSuperfactor = 1.0f / (constrainf(1.0f - (ABS(rcCommandf) * (currentControlRateProfile->rates[axis] / 100.0f)), 0.01f, 1.00f));
if (currentProfile->pidProfile.pidController == PID_CONTROLLER_BETAFLIGHT) {
ptermSetpointRate[axis] = constrainf(angleRate * rcSuperfactor, -1998.0f, 1998.0f);
if (currentProfile->pidProfile.ptermSRateWeight < 100 && axis != YAW && !flightModeFlags) {
const float pWeight = currentProfile->pidProfile.ptermSRateWeight / 100.0f;
angleRate = angleRate + (pWeight * ptermSetpointRate[axis] - angleRate);
} else {
angleRate = ptermSetpointRate[axis];
}
} else {
angleRate *= rcSuperfactor;
}
} else {
if (currentProfile->pidProfile.pidController == PID_CONTROLLER_BETAFLIGHT) ptermSetpointRate[axis] = angleRate;
}
if (debugMode == DEBUG_ANGLERATE) {
debug[axis] = angleRate;

View File

@ -47,11 +47,8 @@
#include "fc/runtime_config.h"
uint32_t targetPidLooptime;
bool pidStabilisationEnabled;
uint8_t PIDweight[3];
int16_t axisPID[3];

View File

@ -89,7 +89,7 @@ typedef struct pidProfile_s {
// Betaflight PID controller parameters
uint8_t itermThrottleGain; // Throttle coupling to iterm. Quick throttle changes will bump iterm
uint8_t ptermSRateWeight; // Setpoint super expo ratio for Pterm (lower means that pretty much only P has super expo rates)
uint8_t setpointRelaxRatio; // Setpoint weight relaxation effect
uint8_t dtermSetpointWeight; // Setpoint weight for Dterm (0= measurement, 1= full error, 1 > agressive derivative)
uint16_t yawRateAccelLimit; // yaw accel limiter for deg/sec/ms
uint16_t rateAccelLimit; // accel limiter roll/pitch deg/sec/ms

View File

@ -50,7 +50,7 @@
#include "flight/gtune.h"
extern float rcInput[3];
extern float setpointRate[3], ptermSetpointRate[3];
extern float setpointRate[3];
extern float errorGyroIf[3];
extern bool pidStabilisationEnabled;
@ -70,10 +70,10 @@ float getdT(void);
void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig)
{
float errorRate = 0, rP = 0, rD = 0, PVRate = 0;
float errorRate = 0, rD = 0, PVRate = 0, dynC;
float ITerm,PTerm,DTerm;
static float lastRateError[2];
static float Kp[3], Ki[3], Kd[3], c[3], rollPitchMaxVelocity, yawMaxVelocity, previousSetpoint[3];
static float Kp[3], Ki[3], Kd[3], c[3], rollPitchMaxVelocity, yawMaxVelocity, previousSetpoint[3], relaxFactor[3];
float delta;
int axis;
float horizonLevelStrength = 1;
@ -126,6 +126,7 @@ void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
Ki[axis] = ITERM_SCALE * pidProfile->I8[axis];
Kd[axis] = DTERM_SCALE * pidProfile->D8[axis];
c[axis] = pidProfile->dtermSetpointWeight / 100.0f;
relaxFactor[axis] = 1.0f - (pidProfile->setpointRelaxRatio / 100.0f);
yawMaxVelocity = pidProfile->yawRateAccelLimit * 1000 * getdT();
rollPitchMaxVelocity = pidProfile->rateAccelLimit * 1000 * getdT();
@ -156,11 +157,11 @@ void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
#endif
if (FLIGHT_MODE(ANGLE_MODE)) {
// ANGLE mode - control is angle based, so control loop is needed
ptermSetpointRate[axis] = setpointRate[axis] = errorAngle * pidProfile->P8[PIDLEVEL] / 10.0f;
setpointRate[axis] = errorAngle * pidProfile->P8[PIDLEVEL] / 10.0f;
} else {
// HORIZON mode - direct sticks control is applied to rate PID
// mix up angle error to desired AngleRate to add a little auto-level feel
ptermSetpointRate[axis] = setpointRate[axis] = setpointRate[axis] + (errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 10.0f);
setpointRate[axis] = setpointRate[axis] + (errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 10.0f);
}
}
@ -171,10 +172,9 @@ void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
// Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes
// ----- calculate error / angle rates ----------
errorRate = setpointRate[axis] - PVRate; // r - y
rP = ptermSetpointRate[axis] - PVRate; // br - y
// -----calculate P component
PTerm = Kp[axis] * rP * tpaFactor;
// -----calculate P component and add Dynamic Part based on stick input
PTerm = Kp[axis] * errorRate * tpaFactor;
// -----calculate I component.
// Reduce strong Iterm accumulation during higher stick inputs
@ -192,7 +192,11 @@ void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
//-----calculate D-term (Yaw D not yet supported)
if (axis != YAW) {
rD = c[axis] * setpointRate[axis] - PVRate; // cr - y
if (pidProfile->setpointRelaxRatio < 100)
dynC = c[axis] * powerf(rcInput[axis], 2) * relaxFactor[axis] + c[axis] * (1-relaxFactor[axis]);
else
dynC = c[axis];
rD = dynC * setpointRate[axis] - PVRate; // cr - y
delta = rD - lastRateError[axis];
lastRateError[axis] = rD;
@ -215,7 +219,7 @@ void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
DTerm = Kd[axis] * delta * tpaFactor;
// -----calculate total PID output
axisPID[axis] = constrain(lrintf(PTerm + ITerm + DTerm), -900, 900);
axisPID[axis] = constrain(lrintf(PTerm + ITerm + DTerm), -800, 800);
} else {
if (pidProfile->yaw_lpf_hz) PTerm = pt1FilterApply4(&yawFilter, PTerm, pidProfile->yaw_lpf_hz, getdT());

View File

@ -81,7 +81,7 @@ uint16_t refreshTimeout = 0;
#define VISIBLE_FLAG 0x0800
#define BLINK_FLAG 0x0400
uint8_t blinkState = 1;
bool blinkState = true;
#define OSD_POS(x,y) (x | (y << 5))
#define OSD_X(x) (x & 0x001F)
@ -141,7 +141,9 @@ bool inMenu = false;
typedef void (* OSDMenuFuncPtr)(void *data);
void osdUpdate(uint32_t currentTime);
void osdUpdate(uint8_t guiKey);
char osdGetAltitudeSymbol();
int32_t osdGetAltitude(int32_t alt);
void osdOpenMenu(void);
void osdExitMenu(void * ptr);
void osdMenuBack(void);
@ -451,7 +453,7 @@ static OSD_FLOAT_t entryRcExpo = {&rateProfile.rcExpo8, 0, 100, 1, 10};
static OSD_FLOAT_t entryRcExpoYaw = {&rateProfile.rcYawExpo8, 0, 100, 1, 10};
static OSD_FLOAT_t extryTpaEntry = {&rateProfile.dynThrPID, 0, 70, 1, 10};
static OSD_UINT16_t entryTpaBreak = {&rateProfile.tpa_breakpoint, 1100, 1800, 10};
static OSD_FLOAT_t entryPSetpoint = {&masterConfig.profile[0].pidProfile.ptermSRateWeight, 0, 100, 1, 10};
static OSD_FLOAT_t entryPSetpoint = {&masterConfig.profile[0].pidProfile.setpointRelaxRatio, 0, 100, 1, 10};
static OSD_FLOAT_t entryDSetpoint = {&masterConfig.profile[0].pidProfile.dtermSetpointWeight, 0, 255, 1, 10};
OSD_Entry menuRateExpo[] =
@ -625,10 +627,36 @@ void osdInit(void)
refreshTimeout = 4 * REFRESH_1S;
}
/**
* Gets the correct altitude symbol for the current unit system
*/
char osdGetAltitudeSymbol()
{
switch (masterConfig.osdProfile.units) {
case OSD_UNIT_IMPERIAL:
return 0xF;
default:
return 0xC;
}
}
/**
* Converts altitude based on the current unit system.
* @param alt Raw altitude (i.e. as taken from BaroAlt)
*/
int32_t osdGetAltitude(int32_t alt)
{
switch (masterConfig.osdProfile.units) {
case OSD_UNIT_IMPERIAL:
return (alt * 328) / 100; // Convert to feet / 100
default:
return alt; // Already in metre / 100
}
}
void osdUpdateAlarms(void)
{
int32_t alt = BaroAlt / 100;
int32_t alt = osdGetAltitude(BaroAlt) / 100;
statRssi = rssi * 100 / 1024;
if (statRssi < OSD_cfg.rssi_alarm)
@ -656,10 +684,6 @@ void osdUpdateAlarms(void)
else
OSD_cfg.item_pos[OSD_MAH_DRAWN] &= ~BLINK_FLAG;
if (masterConfig.osdProfile.units == OSD_UNIT_IMPERIAL) {
alt = (alt * 328) / 100; // Convert to feet
}
if (alt >= OSD_cfg.alt_alarm)
OSD_cfg.item_pos[OSD_ALTITUDE] |= BLINK_FLAG;
else
@ -1045,6 +1069,7 @@ void osdResetStats(void)
stats.min_voltage = 500;
stats.max_current = 0;
stats.min_rssi = 99;
stats.max_altitude = 0;
}
void osdUpdateStats(void)
@ -1064,6 +1089,9 @@ void osdUpdateStats(void)
if (stats.min_rssi > statRssi)
stats.min_rssi = statRssi;
if (stats.max_altitude < BaroAlt)
stats.max_altitude = BaroAlt;
}
void osdShowStats(void)
@ -1100,6 +1128,12 @@ void osdShowStats(void)
strcat(buff, "\x07");
max7456Write(22, top++, buff);
}
max7456Write(2, top, "MAX ALTITUDE :");
int32_t alt = osdGetAltitude(stats.max_altitude);
sprintf(buff, "%c%d.%01d%c", alt < 0 ? '-' : ' ', abs(alt / 100), abs((alt % 100) / 10), osdGetAltitudeSymbol());
max7456Write(22, top++, buff);
refreshTimeout = 60 * REFRESH_1S;
}
@ -1135,7 +1169,7 @@ void updateOsd(uint32_t currentTime)
void osdUpdate(uint32_t currentTime)
{
static uint8_t rcDelay = BUTTON_TIME;
static uint8_t last_sec = 0;
static uint8_t lastSec = 0;
uint8_t key = 0, sec;
// detect enter to menu
@ -1156,9 +1190,9 @@ void osdUpdate(uint32_t currentTime)
sec = currentTime / 1000000;
if (ARMING_FLAG(ARMED) && sec != last_sec) {
if (ARMING_FLAG(ARMED) && sec != lastSec) {
flyTime++;
last_sec = sec;
lastSec = sec;
}
if (refreshTimeout) {
@ -1407,7 +1441,10 @@ void osdDrawElements(void)
if (currentElement)
osdDrawElementPositioningHelp();
else if (sensors(SENSOR_ACC) || inMenu)
{
osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON);
osdDrawSingleElement(OSD_CROSSHAIRS);
}
osdDrawSingleElement(OSD_MAIN_BATT_VOLTAGE);
osdDrawSingleElement(OSD_RSSI_VALUE);
@ -1494,18 +1531,8 @@ void osdDrawSingleElement(uint8_t item)
case OSD_ALTITUDE:
{
int32_t alt = BaroAlt; // Metre x 100
char unitSym = 0xC; // m
if (!VISIBLE(OSD_cfg.item_pos[OSD_ALTITUDE]) || BLINK(OSD_cfg.item_pos[OSD_ALTITUDE]))
return;
if (masterConfig.osdProfile.units == OSD_UNIT_IMPERIAL) {
alt = (alt * 328) / 100; // Convert to feet x 100
unitSym = 0xF; // ft
}
sprintf(buff, "%c%d.%01d%c", alt < 0 ? '-' : ' ', abs(alt / 100), abs((alt % 100) / 10), unitSym);
int32_t alt = osdGetAltitude(BaroAlt);
sprintf(buff, "%c%d.%01d%c", alt < 0 ? '-' : ' ', abs(alt / 100), abs((alt % 100) / 10), osdGetAltitudeSymbol());
break;
}
@ -1573,6 +1600,21 @@ void osdDrawSingleElement(uint8_t item)
}
#endif // VTX
case OSD_CROSSHAIRS:
{
uint8_t *screenBuffer = max7456GetScreenBuffer();
uint16_t position = 194;
if (maxScreenSize == VIDEO_BUFFER_CHARS_PAL)
position += 30;
screenBuffer[position - 1] = (SYM_AH_CENTER_LINE);
screenBuffer[position + 1] = (SYM_AH_CENTER_LINE_RIGHT);
screenBuffer[position] = (SYM_AH_CENTER);
return;
}
case OSD_ARTIFICIAL_HORIZON:
{
uint8_t *screenBuffer = max7456GetScreenBuffer();
@ -1584,7 +1626,6 @@ void osdDrawSingleElement(uint8_t item)
if (maxScreenSize == VIDEO_BUFFER_CHARS_PAL)
position += 30;
if (pitchAngle > AH_MAX_PITCH)
pitchAngle = AH_MAX_PITCH;
if (pitchAngle < -AH_MAX_PITCH)
@ -1595,8 +1636,6 @@ void osdDrawSingleElement(uint8_t item)
rollAngle = -AH_MAX_ROLL;
for (uint8_t x = 0; x <= 8; x++) {
if (x == 4)
x = 5;
int y = (rollAngle * (4 - x)) / 64;
y -= pitchAngle / 8;
y += 41;
@ -1606,11 +1645,8 @@ void osdDrawSingleElement(uint8_t item)
}
}
screenBuffer[position - 1] = (SYM_AH_CENTER_LINE);
screenBuffer[position + 1] = (SYM_AH_CENTER_LINE_RIGHT);
screenBuffer[position] = (SYM_AH_CENTER);
osdDrawSingleElement(OSD_HORIZON_SIDEBARS);
return;
}

View File

@ -22,6 +22,7 @@
typedef enum {
OSD_RSSI_VALUE,
OSD_MAIN_BATT_VOLTAGE,
OSD_CROSSHAIRS,
OSD_ARTIFICIAL_HORIZON,
OSD_HORIZON_SIDEBARS,
OSD_ONTIME,
@ -61,6 +62,7 @@ typedef struct {
int16_t min_voltage; // /10
int16_t max_current; // /10
int16_t min_rssi;
int16_t max_altitude;
} statistic_t;
void updateOsd(uint32_t currentTime);

View File

@ -795,8 +795,10 @@ const clivalue_t valueTable[] = {
{ "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } },
{ "gyro_lowpass_level", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_soft_type, .config.lookup = { TABLE_LOWPASS_TYPE } },
{ "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 255 } },
{ "gyro_notch_hz", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_hz, .config.minmax = { 0, 500 } },
{ "gyro_notch_cutoff", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_cutoff, .config.minmax = { 1, 500 } },
{ "gyro_notch_hz_1", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_hz_1, .config.minmax = { 0, 1000 } },
{ "gyro_notch_cutoff_1", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_cutoff_1, .config.minmax = { 1, 1000 } },
{ "gyro_notch_hz_2", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_hz_2, .config.minmax = { 0, 1000 } },
{ "gyro_notch_cutoff_2", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_cutoff_2, .config.minmax = { 1, 1000 } },
{ "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } },
{ "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
{ "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
@ -873,7 +875,7 @@ const clivalue_t valueTable[] = {
{ "vbat_pid_compensation", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
{ "pid_at_min_throttle", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidAtMinThrottle, .config.lookup = { TABLE_OFF_ON } },
{ "iterm_throttle_gain", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermThrottleGain, .config.minmax = {0, 200 } },
{ "pterm_srate_ratio", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.ptermSRateWeight, .config.minmax = {0, 100 } },
{ "setpoint_relax_ratio", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.setpointRelaxRatio, .config.minmax = {0, 100 } },
{ "dterm_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dtermSetpointWeight, .config.minmax = {0, 255 } },
{ "yaw_rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawRateAccelLimit, .config.minmax = {0, 1000 } },
{ "rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rateAccelLimit, .config.minmax = {0, 1000 } },
@ -939,6 +941,7 @@ const clivalue_t valueTable[] = {
#ifdef OSD
{ "osd_video_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.video_system, .config.minmax = { 0, 2 } },
{ "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.osdProfile.units, .config.lookup = { TABLE_UNIT } },
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.rssi_alarm, .config.minmax = { 0, 100 } },
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.cap_alarm, .config.minmax = { 0, 20000 } },
{ "osd_time_alarm", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.time_alarm, .config.minmax = { 0, 60 } },
@ -951,13 +954,14 @@ const clivalue_t valueTable[] = {
{ "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_FLYMODE], .config.minmax = { 0, 65536 } },
{ "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], .config.minmax = { 0, 65536 } },
{ "osd_vtx_channel_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL], .config.minmax = { 0, 65536 } },
{ "osd_crosshairs", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CROSSHAIRS], .config.minmax = { 0, 65536 } },
{ "osd_artificial_horizon", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { 0, 65536 } },
{ "osd_current_draw_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW], .config.minmax = { 0, 65536 } },
{ "osd_mah_drawn_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN], .config.minmax = { 0, 65536 } },
{ "osd_craft_name_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME], .config.minmax = { 0, 65536 } },
{ "osd_gps_speed_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_GPS_SPEED], .config.minmax = { 0, 65536 } },
{ "osd_gps_sats_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_GPS_SATS], .config.minmax = { 0, 65536 } },
{ "osd_altitude", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ALTITUDE], .config.minmax = { 0, 65536 } },
{ "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ALTITUDE], .config.minmax = { 0, 65536 } },
#endif
};

View File

@ -269,6 +269,7 @@ void init(void)
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
#endif
#ifdef STM32F303xC
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
pwm_params.useUART3 = doesConfigurationUsePort(SERIAL_PORT_USART3);
#endif
#if defined(USE_UART2) && defined(STM32F40_41xxx)
@ -402,7 +403,7 @@ void init(void)
}
#endif
#if defined(SPRACINGF3MINI) || defined(OMNIBUS)
#if defined(SPRACINGF3MINI) || defined(OMNIBUS) || defined(X_RACERSPI)
#if defined(SONAR) && defined(USE_SOFTSERIAL1)
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
serialRemovePort(SERIAL_PORT_SOFTSERIAL1);
@ -680,7 +681,7 @@ void main_init(void)
/* Setup scheduler */
schedulerInit();
rescheduleTask(TASK_GYROPID, gyro.targetLooptime + LOOPTIME_SUSPEND_TIME); // Add a littlebit of extra time to reduce busy wait
rescheduleTask(TASK_GYROPID, gyro.targetLooptime);
setTaskEnabled(TASK_GYROPID, true);
if (sensors(SENSOR_ACC)) {

View File

@ -59,7 +59,7 @@
#define MSP_PROTOCOL_VERSION 0
#define API_VERSION_MAJOR 1 // increment when major changes are made
#define API_VERSION_MINOR 20 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
#define API_VERSION_MINOR 21 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
#define API_VERSION_LENGTH 2

View File

@ -1246,14 +1246,16 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize16(masterConfig.motorConfig.motorPwmRate);
break;
case MSP_FILTER_CONFIG :
headSerialReply(13);
headSerialReply(17);
serialize8(masterConfig.gyro_soft_lpf_hz);
serialize16(currentProfile->pidProfile.dterm_lpf_hz);
serialize16(currentProfile->pidProfile.yaw_lpf_hz);
serialize16(masterConfig.gyro_soft_notch_hz);
serialize16(masterConfig.gyro_soft_notch_cutoff);
serialize16(masterConfig.gyro_soft_notch_hz_1);
serialize16(masterConfig.gyro_soft_notch_cutoff_1);
serialize16(currentProfile->pidProfile.dterm_notch_hz);
serialize16(currentProfile->pidProfile.dterm_notch_cutoff);
serialize16(masterConfig.gyro_soft_notch_hz_2);
serialize16(masterConfig.gyro_soft_notch_cutoff_2);
break;
case MSP_PID_ADVANCED:
headSerialReply(17);
@ -1262,7 +1264,7 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize16(currentProfile->pidProfile.yaw_p_limit);
serialize8(currentProfile->pidProfile.deltaMethod);
serialize8(currentProfile->pidProfile.vbatPidCompensation);
serialize8(currentProfile->pidProfile.ptermSRateWeight);
serialize8(currentProfile->pidProfile.setpointRelaxRatio);
serialize8(currentProfile->pidProfile.dtermSetpointWeight);
serialize8(0); // reserved
serialize8(0); // reserved
@ -1857,11 +1859,15 @@ static bool processInCommand(void)
currentProfile->pidProfile.dterm_lpf_hz = read16();
currentProfile->pidProfile.yaw_lpf_hz = read16();
if (currentPort->dataSize > 5) {
masterConfig.gyro_soft_notch_hz = read16();
masterConfig.gyro_soft_notch_cutoff = read16();
masterConfig.gyro_soft_notch_hz_1 = read16();
masterConfig.gyro_soft_notch_cutoff_1 = read16();
currentProfile->pidProfile.dterm_notch_hz = read16();
currentProfile->pidProfile.dterm_notch_cutoff = read16();
}
if (currentPort->dataSize > 13) {
serialize16(masterConfig.gyro_soft_notch_hz_2);
serialize16(masterConfig.gyro_soft_notch_cutoff_2);
}
break;
case MSP_SET_PID_ADVANCED:
currentProfile->pidProfile.rollPitchItermIgnoreRate = read16();
@ -1869,7 +1875,7 @@ static bool processInCommand(void)
currentProfile->pidProfile.yaw_p_limit = read16();
currentProfile->pidProfile.deltaMethod = read8();
currentProfile->pidProfile.vbatPidCompensation = read8();
currentProfile->pidProfile.ptermSRateWeight = read8();
currentProfile->pidProfile.setpointRelaxRatio = read8();
currentProfile->pidProfile.dtermSetpointWeight = read8();
read8(); // reserved
read8(); // reserved

1
src/main/scheduler/scheduler.h Executable file → Normal file
View File

@ -119,7 +119,6 @@ typedef struct {
} cfTask_t;
extern cfTask_t cfTasks[TASK_COUNT];
extern uint16_t cpuLoad;
extern uint16_t averageSystemLoadPercent;
void getTaskInfo(cfTaskId_e taskId, cfTaskInfo_t * taskInfo);

View File

@ -47,29 +47,38 @@ float gyroADCf[XYZ_AXIS_COUNT];
static int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 };
static const gyroConfig_t *gyroConfig;
static biquadFilter_t gyroFilterLPF[XYZ_AXIS_COUNT];
static biquadFilter_t gyroFilterNotch[XYZ_AXIS_COUNT];
static biquadFilter_t gyroFilterNotch_1[XYZ_AXIS_COUNT], gyroFilterNotch_2[XYZ_AXIS_COUNT];
static pt1Filter_t gyroFilterPt1[XYZ_AXIS_COUNT];
static uint8_t gyroSoftLpfType;
static uint16_t gyroSoftNotchHz;
static float gyroSoftNotchQ;
static uint16_t gyroSoftNotchHz_1, gyroSoftNotchHz_2;
static float gyroSoftNotchQ_1, gyroSoftNotchQ_2;
static uint8_t gyroSoftLpfHz;
static uint16_t calibratingG = 0;
static float gyroDt;
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz, uint16_t gyro_soft_notch_hz, uint16_t gyro_soft_notch_cutoff, uint8_t gyro_soft_lpf_type)
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse,
uint8_t gyro_soft_lpf_hz,
uint16_t gyro_soft_notch_hz_1,
uint16_t gyro_soft_notch_cutoff_1,
uint16_t gyro_soft_notch_hz_2,
uint16_t gyro_soft_notch_cutoff_2,
uint8_t gyro_soft_lpf_type)
{
gyroConfig = gyroConfigToUse;
gyroSoftLpfHz = gyro_soft_lpf_hz;
gyroSoftNotchHz = gyro_soft_notch_hz;
gyroSoftNotchHz_1 = gyro_soft_notch_hz_1;
gyroSoftNotchHz_2 = gyro_soft_notch_hz_2;
gyroSoftLpfType = gyro_soft_lpf_type;
gyroSoftNotchQ = filterGetNotchQ(gyro_soft_notch_hz, gyro_soft_notch_cutoff);
gyroSoftNotchQ_1 = filterGetNotchQ(gyro_soft_notch_hz_1, gyro_soft_notch_cutoff_1);
gyroSoftNotchQ_2 = filterGetNotchQ(gyro_soft_notch_hz_2, gyro_soft_notch_cutoff_2);
}
void gyroInit(void)
{
if (gyroSoftLpfHz && gyro.targetLooptime) { // Initialisation needs to happen once samplingrate is known
for (int axis = 0; axis < 3; axis++) {
biquadFilterInit(&gyroFilterNotch[axis], gyroSoftNotchHz, gyro.targetLooptime, gyroSoftNotchQ, FILTER_NOTCH);
biquadFilterInit(&gyroFilterNotch_1[axis], gyroSoftNotchHz_1, gyro.targetLooptime, gyroSoftNotchQ_1, FILTER_NOTCH);
biquadFilterInit(&gyroFilterNotch_2[axis], gyroSoftNotchHz_2, gyro.targetLooptime, gyroSoftNotchQ_2, FILTER_NOTCH);
if (gyroSoftLpfType == FILTER_BIQUAD)
biquadFilterInitLPF(&gyroFilterLPF[axis], gyroSoftLpfHz, gyro.targetLooptime);
else
@ -184,8 +193,11 @@ void gyroUpdate(void)
if (debugMode == DEBUG_NOTCH)
debug[axis] = lrintf(gyroADCf[axis]);
if (gyroSoftNotchHz)
gyroADCf[axis] = biquadFilterApply(&gyroFilterNotch[axis], gyroADCf[axis]);
if (gyroSoftNotchHz_1)
gyroADCf[axis] = biquadFilterApply(&gyroFilterNotch_1[axis], gyroADCf[axis]);
if (gyroSoftNotchHz_2)
gyroADCf[axis] = biquadFilterApply(&gyroFilterNotch_2[axis], gyroADCf[axis]);
gyroADC[axis] = lrintf(gyroADCf[axis]);
}

View File

@ -41,7 +41,13 @@ typedef struct gyroConfig_s {
uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
} gyroConfig_t;
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz, uint16_t gyro_soft_notch_hz, uint16_t gyro_soft_notch_cutoff, uint8_t gyro_soft_lpf_type);
void gyroUseConfig(const gyroConfig_t *gyroConfigToUse,
uint8_t gyro_soft_lpf_hz,
uint16_t gyro_soft_notch_hz_1,
uint16_t gyro_soft_notch_cutoff_1,
uint16_t gyro_soft_notch_hz_2,
uint16_t gyro_soft_notch_cutoff_2,
uint8_t gyro_soft_lpf_type);
void gyroSetCalibrationCycles(void);
void gyroInit(void);
void gyroUpdate(void);

View File

@ -114,8 +114,20 @@
#define USE_ADC
#define CURRENT_METER_ADC_PIN PC1
#define VBAT_ADC_PIN PC2
#define RSSI_ADC_PIN PA0
//#define RSSI_ADC_PIN PA0
#define LED_STRIP
// LED Strip can run off Pin 5 (PA1) of the MOTOR outputs.
#define WS2811_GPIO_AF GPIO_AF_TIM5
#define WS2811_PIN PA1
#define WS2811_TIMER TIM5
#define WS2811_TIMER_CHANNEL TIM_Channel_2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST4_HANDLER
#define WS2811_DMA_STREAM DMA1_Stream4
#define WS2811_DMA_CHANNEL DMA_Channel_6
#define WS2811_DMA_IRQ DMA1_Stream4_IRQn
#define WS2811_DMA_FLAG DMA_FLAG_TCIF4
#define WS2811_DMA_IT DMA_IT_TCIF4
#define SENSORS_SET (SENSOR_ACC)

View File

@ -5,6 +5,8 @@ TARGET_SRC = \
drivers/accgyro_spi_mpu6000.c \
drivers/barometer_ms5611.c \
drivers/compass_hmc5883l.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f4xx.c \
drivers/max7456.c \
io/osd.c

View File

@ -109,17 +109,17 @@
//#define RSSI_ADC_PIN PA0
#define LED_STRIP
// LED Strip can run off Pin 6 (PA0) of the MOTOR outputs.
// LED Strip can run off Pin 5 (PA1) of the MOTOR outputs.
#define WS2811_GPIO_AF GPIO_AF_TIM5
#define WS2811_PIN PA0
#define WS2811_PIN PA1
#define WS2811_TIMER TIM5
#define WS2811_TIMER_CHANNEL TIM_Channel_2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER
#define WS2811_DMA_STREAM DMA1_Stream2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST4_HANDLER
#define WS2811_DMA_STREAM DMA1_Stream4
#define WS2811_DMA_CHANNEL DMA_Channel_6
#define WS2811_DMA_IRQ DMA1_Stream2_IRQn
#define WS2811_DMA_FLAG DMA_FLAG_TCIF2
#define WS2811_DMA_IT DMA_IT_TCIF2
#define WS2811_DMA_IRQ DMA1_Stream4_IRQn
#define WS2811_DMA_FLAG DMA_FLAG_TCIF4
#define WS2811_DMA_IT DMA_IT_TCIF4
#define SENSORS_SET (SENSOR_ACC)

View File

@ -0,0 +1,102 @@
/*
* 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 "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM3 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
0xFFFF
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
0xFFFF
};
const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM2 | (MAP_TO_SERVO_OUTPUT << 8),
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
0xFFFF
};
const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S2_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S2_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S6_OUT
};

View File

@ -0,0 +1,124 @@
/*
* 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/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "SOUL"
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define USBD_PRODUCT_STRING "DemonSoulF4"
#ifdef OPBL
#define USBD_SERIALNUMBER_STRING "0x8020000"
#endif
#define LED0 PB5
#define LED1 PB4
#define BEEPER PB6
#define BEEPER_INVERTED
#define INVERTER PC0 // PC0 used as inverter select GPIO
#define INVERTER_USART USART1
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define ACC
#define USE_ACC_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
// MPU6000 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled)
#define M25P16_CS_PIN PB3
#define M25P16_SPI_INSTANCE SPI3
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USE_VCP
#define VBUS_SENSING_PIN PC5
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PB3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_ADC
#define VBAT_ADC_PIN PC2
#define SENSORS_SET (SENSOR_ACC)
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define LED_STRIP
#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_IT DMA_IT_TCIF2
#define WS2811_DMA_CHANNEL DMA_Channel_6
#define WS2811_TIMER_CHANNEL TIM_Channel_1
#define SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define USABLE_TIMER_CHANNEL_COUNT 12
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) )

View File

@ -0,0 +1,8 @@
F405_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro_spi_mpu6000.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f4xx.c

View File

@ -10,18 +10,18 @@
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
0xFFFF
};
@ -32,33 +32,31 @@ const uint16_t multiPWM[] = {
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8),
PWM7 | (MAP_TO_PWM_INPUT << 8),
PWM8 | (MAP_TO_PWM_INPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
PWM16 | (MAP_TO_SERVO_OUTPUT << 8),
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10
PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10
0xFFFF
};
@ -68,17 +66,15 @@ const uint16_t airPWM[] = {
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8),
PWM7 | (MAP_TO_PWM_INPUT << 8),
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // server #6
PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #6
0xFFFF
};
@ -87,10 +83,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1

View File

@ -66,8 +66,8 @@
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 6 // PWM 5
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 7 // PWM 6
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
#define USE_I2C

View File

@ -1,6 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = ONBOARDFLASH
TARGET_FLAGS = -DSPRACINGF3
TARGET_SRC = \
drivers/accgyro_mpu.c \