Merge branch 'master' into development

This commit is contained in:
borisbstyle 2016-09-11 01:16:53 +02:00
commit 05908aad4d
36 changed files with 957 additions and 183 deletions

View File

@ -1282,11 +1282,8 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("pidAtMinThrottle:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.pidAtMinThrottle);
// Betaflight PID controller parameters
BLACKBOX_PRINT_HEADER_LINE("toleranceBand:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.toleranceBand);
BLACKBOX_PRINT_HEADER_LINE("toleranceBandReduction:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.toleranceBandReduction);
BLACKBOX_PRINT_HEADER_LINE("zeroCrossAllowanceCount:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.zeroCrossAllowanceCount);
BLACKBOX_PRINT_HEADER_LINE("itermThrottleGain:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.itermThrottleGain);
BLACKBOX_PRINT_HEADER_LINE("ptermSetpointWeight:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.ptermSetpointWeight);
BLACKBOX_PRINT_HEADER_LINE("ptermSRateWeight:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.ptermSRateWeight);
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);

View File

@ -99,6 +99,13 @@ float acos_approx(float x)
}
#endif
float powerf(float base, int exp) {
float result = base;
for (int count = 1; count < exp; count++) result *= base;
return result;
}
int32_t applyDeadband(int32_t value, int32_t deadband)
{
if (ABS(value) < deadband) {

View File

@ -69,6 +69,7 @@ typedef union {
fp_angles_def angles;
} fp_angles_t;
float powerf(float base, int exp);
int32_t applyDeadband(int32_t value, int32_t deadband);
void devClear(stdev_t *dev);

View File

@ -139,7 +139,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->P8[PITCH] = 60;
pidProfile->I8[PITCH] = 65;
pidProfile->D8[PITCH] = 22;
pidProfile->P8[YAW] = 80;
pidProfile->P8[YAW] = 70;
pidProfile->I8[YAW] = 45;
pidProfile->D8[YAW] = 20;
pidProfile->P8[PIDALT] = 50;
@ -163,7 +163,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->D8[PIDVEL] = 75;
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
pidProfile->yaw_lpf_hz = 80;
pidProfile->yaw_lpf_hz = 0;
pidProfile->rollPitchItermIgnoreRate = 130;
pidProfile->yawItermIgnoreRate = 32;
pidProfile->dterm_filter_type = FILTER_BIQUAD;
@ -175,13 +175,10 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
// Betaflight PID controller parameters
pidProfile->ptermSetpointWeight = 80;
pidProfile->ptermSRateWeight = 85;
pidProfile->dtermSetpointWeight = 150;
pidProfile->yawRateAccelLimit = 220;
pidProfile->rateAccelLimit = 0;
pidProfile->toleranceBand = 0;
pidProfile->toleranceBandReduction = 40;
pidProfile->zeroCrossAllowanceCount = 2;
pidProfile->itermThrottleGain = 0;
#ifdef GTUNE
@ -248,6 +245,7 @@ void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig)
escAndServoConfig->maxthrottle = 2000;
escAndServoConfig->mincommand = 1000;
escAndServoConfig->servoCenterPulse = 1500;
escAndServoConfig->maxEscThrottleJumpMs = 0;
}
void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
@ -261,7 +259,7 @@ void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
#ifdef TELEMETRY
void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
{
telemetryConfig->telemetry_inversion = 0;
telemetryConfig->telemetry_inversion = 1;
telemetryConfig->telemetry_switch = 0;
telemetryConfig->gpsNoFixLatitude = 0;
telemetryConfig->gpsNoFixLongitude = 0;
@ -420,7 +418,7 @@ void createDefaultConfig(master_t *config)
config->gyro_soft_type = FILTER_PT1;
config->gyro_soft_lpf_hz = 90;
config->gyro_soft_notch_hz = 0;
config->gyro_soft_notch_cutoff = 150;
config->gyro_soft_notch_cutoff = 130;
config->debug_mode = DEBUG_NONE;
@ -787,12 +785,6 @@ void validateAndFixConfig(void)
}
#endif
#ifdef STM32F303xC
// hardware supports serial port inversion, make users life easier for those that want to connect SBus RX's
masterConfig.telemetryConfig.telemetry_inversion = 1;
#endif
/*#if defined(LED_STRIP) && defined(TRANSPONDER) // TODO - Add transponder feature
if ((WS2811_DMA_TC_FLAG == TRANSPONDER_DMA_TC_FLAG) && featureConfigured(FEATURE_TRANSPONDER) && featureConfigured(FEATURE_LED_STRIP)) {
featureClear(FEATURE_LED_STRIP);

2
src/main/drivers/max7456.c Normal file → Executable file
View File

@ -297,7 +297,7 @@ void max7456_write_nvm(uint8_t char_address, uint8_t *font_data) {
max7456_send(MAX7456ADD_CMM, WRITE_NVR);
// wait until bit 5 in the status register returns to 0 (12ms)
while ((spiTransferByte(MAX7456_SPI_INSTANCE, MAX7456ADD_STAT) & STATUS_REG_NVR_BUSY) != 0);
while ((max7456_send(MAX7456ADD_STAT, 0) & STATUS_REG_NVR_BUSY) != 0x00);
max7456_send(VM0_REG, video_signal_type | 0x0C);
DISABLE_MAX7456;

View File

@ -242,6 +242,12 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
}
#endif
#if defined(SPRACINGF3EVO)
// remap PWM6+7 as servos
if ((timerIndex == PWM8 || timerIndex == PWM9) && timerHardwarePtr->tim == TIM3)
type = MAP_TO_SERVO_OUTPUT;
#endif
#if (defined(STM32F3DISCOVERY) && !defined(CHEBUZZF3))
// remap PWM 5+6 or 9+10 as servos - softserial pin pairs require timer ports that use the same timer
if (init->useSoftSerial) {

View File

@ -114,4 +114,17 @@ void systemInit(void)
void checkForBootLoaderRequest(void)
{
void(*bootJump)(void);
if (*((uint32_t *)0x20004FF0) == 0xDEADBEEF) {
*((uint32_t *)0x20004FF0) = 0x0;
__enable_irq();
__set_MSP(*((uint32_t *)0x1FFFF000));
bootJump = (void(*)(void))(*((uint32_t *) 0x1FFFF004));
bootJump();
while (1);
}
}

View File

@ -107,4 +107,17 @@ void systemInit(void)
void checkForBootLoaderRequest(void)
{
void(*bootJump)(void);
if (*((uint32_t *)0x20009FFC) == 0xDEADBEEF) {
*((uint32_t *)0x20009FFC) = 0x0;
__enable_irq();
__set_MSP(*((uint32_t *)0x1FFFD800));
bootJump = (void(*)(void))(*((uint32_t *) 0x1FFFD804));
bootJump();
while (1);
}
}

View File

@ -196,9 +196,9 @@ void checkForBootLoaderRequest(void)
*((uint32_t *)0x2001FFFC) = 0x0;
__enable_irq();
__set_MSP(0x20001000);
__set_MSP(*((uint32_t *)0x1FFF0000));
bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004));
bootJump = (void(*)(void))(*((uint32_t *) 0x1FFF0004));
bootJump();
while (1);
}

View File

@ -124,7 +124,7 @@ extern uint8_t PIDweight[3];
uint16_t filteredCycleTime;
static bool isRXDataNew;
static bool armingCalibrationWasInitialised;
float setpointRate[3];
float setpointRate[3], ptermSetpointRate[3];
float rcInput[3];
extern pidControllerFuncPtr pid_controller;
@ -175,8 +175,9 @@ bool isCalibrating()
}
#define RC_RATE_INCREMENTAL 14.54f
#define RC_EXPO_POWER 3
float calculateSetpointRate(int axis, int16_t rc) {
void calculateSetpointRate(int axis, int16_t rc) {
float angleRate, rcRate, rcSuperfactor, rcCommandf;
uint8_t rcExpo;
@ -194,14 +195,26 @@ float calculateSetpointRate(int axis, int16_t rc) {
if (rcExpo) {
float expof = rcExpo / 100.0f;
rcCommandf = rcCommandf * (expof * (rcInput[axis] * rcInput[axis] * rcInput[axis]) + rcInput[axis]*(1-expof));
rcCommandf = rcCommandf * powerf(rcInput[axis], RC_EXPO_POWER) * expof + rcCommandf * (1-expof);
}
angleRate = 200.0f * rcRate * rcCommandf;
if (currentControlRateProfile->rates[axis]) {
rcSuperfactor = 1.0f / (constrainf(1.0f - (rcInput[axis] * (currentControlRateProfile->rates[axis] / 100.0f)), 0.01f, 1.00f));
angleRate *= rcSuperfactor;
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) {
@ -209,9 +222,9 @@ float calculateSetpointRate(int axis, int16_t rc) {
}
if (currentProfile->pidProfile.pidController == PID_CONTROLLER_LEGACY)
return constrainf(angleRate * 4.1f, -8190.0f, 8190.0f); // Rate limit protection
setpointRate[axis] = constrainf(angleRate * 4.1f, -8190.0f, 8190.0f); // Rate limit protection
else
return constrainf(angleRate, -1998.0f, 1998.0f); // Rate limit protection (deg/sec)
setpointRate[axis] = constrainf(angleRate, -1998.0f, 1998.0f); // Rate limit protection (deg/sec)
}
void scaleRcCommandToFpvCamAngle(void) {
@ -290,7 +303,7 @@ void processRcCommand(void)
if (masterConfig.rxConfig.fpvCamAngleDegrees && IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX) && !FLIGHT_MODE(HEADFREE_MODE))
scaleRcCommandToFpvCamAngle();
for (int axis = 0; axis < 3; axis++) setpointRate[axis] = calculateSetpointRate(axis, rcCommand[axis]);
for (int axis = 0; axis < 3; axis++) calculateSetpointRate(axis, rcCommand[axis]);
isRXDataNew = false;
}
@ -573,6 +586,8 @@ void processRx(void)
if (ARMING_FLAG(ARMED)
&& feature(FEATURE_MOTOR_STOP)
&& !STATE(FIXED_WING)
&& !feature(FEATURE_3D)
&& !isAirmodeActive()
) {
if (isUsingSticksForArming()) {
if (throttleStatus == THROTTLE_LOW) {

View File

@ -863,6 +863,19 @@ void mixTable(void *pidProfilePtr)
}
}
// Anti Desync feature for ESC's. Limit rapid throttle changes
if (escAndServoConfig->maxEscThrottleJumpMs) {
const int16_t maxThrottleStep = constrain(escAndServoConfig->maxEscThrottleJumpMs / (1000 / targetPidLooptime), 2, 10000);
// Only makes sense when it's within the range
if (maxThrottleStep < throttleRange) {
static int16_t motorPrevious[MAX_SUPPORTED_MOTORS];
motor[i] = constrain(motor[i], escAndServoConfig->minthrottle, motorPrevious[i] + maxThrottleStep); // Only limit accelerating situation
motorPrevious[i] = motor[i];
}
}
// Disarmed mode
if (!ARMING_FLAG(ARMED)) {
for (i = 0; i < motorCount; i++) {

View File

@ -62,11 +62,6 @@ typedef enum {
SUPEREXPO_YAW_ALWAYS
} pidSuperExpoYaw_e;
typedef enum {
NEGATIVE_ERROR = 0,
POSITIVE_ERROR
} pidErrorPolarity_e;
typedef enum {
PID_STABILISATION_OFF = 0,
PID_STABILISATION_ON
@ -93,11 +88,8 @@ typedef struct pidProfile_s {
uint8_t pidAtMinThrottle; // Disable/Enable pids on zero throttle. Normally even without airmode P and D would be active.
// Betaflight PID controller parameters
uint8_t toleranceBand; // Error tolerance area where toleranceBandReduction is applied under certain circumstances
uint8_t toleranceBandReduction; // Lowest possible P and D reduction in percentage
uint8_t zeroCrossAllowanceCount; // Amount of bouncebacks within tolerance band allowed before reduction kicks in
uint8_t itermThrottleGain; // Throttle coupling to iterm. Quick throttle changes will bump iterm
uint8_t ptermSetpointWeight; // Setpoint weight for Pterm (lower means more PV tracking)
uint8_t ptermSRateWeight; // Setpoint super expo ratio for Pterm (lower means that pretty much only P has super expo rates)
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];
extern float setpointRate[3], ptermSetpointRate[3];
extern float errorGyroIf[3];
extern bool pidStabilisationEnabled;
@ -67,12 +67,13 @@ float getdT(void);
// Betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage.
// Based on 2DOF reference design (matlab)
void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig)
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 ITerm,PTerm,DTerm;
static float lastRateError[2];
static float Kp[3], Ki[3], Kd[3], b[3], c[3], rollPitchMaxVelocity, yawMaxVelocity, previousSetpoint[3];
static float Kp[3], Ki[3], Kd[3], c[3], rollPitchMaxVelocity, yawMaxVelocity, previousSetpoint[3];
float delta;
int axis;
float horizonLevelStrength = 1;
@ -124,7 +125,6 @@ void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
Kp[axis] = PTERM_SCALE * pidProfile->P8[axis];
Ki[axis] = ITERM_SCALE * pidProfile->I8[axis];
Kd[axis] = DTERM_SCALE * pidProfile->D8[axis];
b[axis] = pidProfile->ptermSetpointWeight / 100.0f;
c[axis] = pidProfile->dtermSetpointWeight / 100.0f;
yawMaxVelocity = pidProfile->yawRateAccelLimit * 1000 * getdT();
rollPitchMaxVelocity = pidProfile->rateAccelLimit * 1000 * getdT();
@ -156,11 +156,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
setpointRate[axis] = errorAngle * pidProfile->P8[PIDLEVEL] / 10.0f;
ptermSetpointRate[axis] = 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
setpointRate[axis] = setpointRate[axis] + (errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 10.0f);
ptermSetpointRate[axis] = setpointRate[axis] = setpointRate[axis] + (errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 10.0f);
}
}
@ -171,42 +171,10 @@ 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 = b[axis] * setpointRate[axis] - PVRate; // br - y
// Slowly restore original setpoint with more stick input
float diffRate = errorRate - rP;
rP += diffRate * rcInput[axis];
// Reduce Hunting effect and jittering near setpoint. Limit multiple zero crossing within deadband and lower PID affect during low error amount
float dynReduction = tpaFactor;
if (pidProfile->toleranceBand) {
const float minReduction = (float)pidProfile->toleranceBandReduction / 100.0f;
static uint8_t zeroCrossCount[3];
static uint8_t currentErrorPolarity[3];
if (ABS(errorRate) < pidProfile->toleranceBand) {
if (zeroCrossCount[axis]) {
if (currentErrorPolarity[axis] == POSITIVE_ERROR) {
if (errorRate < 0 ) {
zeroCrossCount[axis]--;
currentErrorPolarity[axis] = NEGATIVE_ERROR;
}
} else {
if (errorRate > 0 ) {
zeroCrossCount[axis]--;
currentErrorPolarity[axis] = POSITIVE_ERROR;
}
}
} else {
dynReduction *= constrainf(ABS(errorRate) / pidProfile->toleranceBand, minReduction, 1.0f);
}
} else {
zeroCrossCount[axis] = pidProfile->zeroCrossAllowanceCount;
currentErrorPolarity[axis] = (errorRate > 0) ? POSITIVE_ERROR : NEGATIVE_ERROR;
}
}
rP = ptermSetpointRate[axis] - PVRate; // br - y
// -----calculate P component
PTerm = Kp[axis] * rP * dynReduction;
PTerm = Kp[axis] * rP * tpaFactor;
// -----calculate I component.
// Reduce strong Iterm accumulation during higher stick inputs
@ -223,13 +191,7 @@ void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
ITerm = errorGyroIf[axis];
//-----calculate D-term (Yaw D not yet supported)
if (axis == YAW) {
if (pidProfile->yaw_lpf_hz) PTerm = pt1FilterApply4(&yawFilter, PTerm, pidProfile->yaw_lpf_hz, getdT());
axisPID[axis] = lrintf(PTerm + ITerm);
DTerm = 0.0f; // needed for blackbox
} else {
if (axis != YAW) {
rD = c[axis] * setpointRate[axis] - PVRate; // cr - y
delta = rD - lastRateError[axis];
lastRateError[axis] = rD;
@ -237,7 +199,7 @@ void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
// Divide delta by targetLooptime to get differential (ie dr/dt)
delta *= (1.0f / getdT());
if (debugMode == DEBUG_DTERM_FILTER) debug[axis] = Kd[axis] * delta * dynReduction;
if (debugMode == DEBUG_DTERM_FILTER) debug[axis] = Kd[axis] * delta * tpaFactor;
// Filter delta
if (dtermNotchInitialised) delta = biquadFilterApply(&dtermFilterNotch[axis], delta);
@ -250,10 +212,16 @@ void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
}
}
DTerm = Kd[axis] * delta * dynReduction;
DTerm = Kd[axis] * delta * tpaFactor;
// -----calculate total PID output
axisPID[axis] = constrain(lrintf(PTerm + ITerm + DTerm), -900, 900);
} else {
if (pidProfile->yaw_lpf_hz) PTerm = pt1FilterApply4(&yawFilter, PTerm, pidProfile->yaw_lpf_hz, getdT());
axisPID[axis] = lrintf(PTerm + ITerm);
DTerm = 0.0f; // needed for blackbox
}
// Disable PID control at zero throttle

View File

@ -24,4 +24,5 @@ typedef struct escAndServoConfig_s {
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
uint16_t maxEscThrottleJumpMs;
} escAndServoConfig_t;

View File

@ -189,9 +189,9 @@ STATIC_UNIT_TESTED void determineLedStripDimensions(void)
STATIC_UNIT_TESTED void determineOrientationLimits(void)
{
highestYValueForNorth = MIN((ledGridHeight / 2) - 1, 0);
highestYValueForNorth = MAX((ledGridHeight / 2) - 1, 0);
lowestYValueForSouth = (ledGridHeight + 1) / 2;
highestXValueForWest = MIN((ledGridWidth / 2) - 1, 0);
highestXValueForWest = MAX((ledGridWidth / 2) - 1, 0);
lowestXValueForEast = (ledGridWidth + 1) / 2;
}

View File

@ -222,7 +222,7 @@ static const char * const featureNames[] = {
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "OSD",
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "SUPEREXPO_RATES", NULL
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", NULL
};
// sync this with rxFailsafeChannelMode_e
@ -672,6 +672,7 @@ const clivalue_t valueTable[] = {
{ "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "max_esc_throttle_jump", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxEscThrottleJumpMs, .config.minmax = { 0, 1000 } },
{ "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_low, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME upper limit should match code in the mixer, 1500 currently
{ "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_high, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME lower limit should match code in the mixer, 1500 currently,
@ -852,11 +853,8 @@ const clivalue_t valueTable[] = {
{ "dterm_notch_cutoff", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_notch_cutoff, .config.minmax = { 1, 500 } },
{ "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 } },
{ "pid_tolerance_band", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.toleranceBand, .config.minmax = {0, 200 } },
{ "tolerance_band_reduction", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.toleranceBandReduction, .config.minmax = {0, 100 } },
{ "zero_cross_allowance", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.zeroCrossAllowanceCount, .config.minmax = {0, 50 } },
{ "iterm_throttle_gain", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermThrottleGain, .config.minmax = {0, 200 } },
{ "pterm_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.ptermSetpointWeight, .config.minmax = {30, 100 } },
{ "pterm_srate_ratio", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.ptermSRateWeight, .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 } },
@ -971,14 +969,24 @@ static void cliShowArgumentRangeError(char *name, int min, int max)
cliPrintf("%s must be between %d and %d\r\n", name, min, max);
}
static char *nextArg(char *currentArg)
{
char *ptr = strchr(currentArg, ' ');
while (ptr && *ptr == ' ') {
ptr++;
}
return ptr;
}
static char *processChannelRangeArgs(char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
{
int val;
for (uint32_t argIndex = 0; argIndex < 2; argIndex++) {
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
val = atoi(++ptr);
val = atoi(ptr);
val = CHANNEL_VALUE_TO_STEP(val);
if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
if (argIndex == 0) {
@ -1061,9 +1069,9 @@ static void cliRxFail(char *cmdline)
rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode;
bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
char *p = strchr(rxFailsafeModeCharacters, *(++ptr));
char *p = strchr(rxFailsafeModeCharacters, *(ptr));
if (p) {
uint8_t requestedMode = p - rxFailsafeModeCharacters;
mode = rxFailsafeModesTable[type][requestedMode];
@ -1077,13 +1085,13 @@ static void cliRxFail(char *cmdline)
requireValue = mode == RX_FAILSAFE_MODE_SET;
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
if (!requireValue) {
cliShowParseError();
return;
}
value = atoi(++ptr);
value = atoi(ptr);
value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
if (value > MAX_RXFAIL_RANGE_STEP) {
cliPrint("Value out of range\r\n");
@ -1167,17 +1175,17 @@ static void cliAux(char *cmdline)
if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
uint8_t validArgumentCount = 0;
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
val = atoi(++ptr);
val = atoi(ptr);
if (val >= 0 && val < CHECKBOX_ITEM_COUNT) {
mac->modeId = val;
validArgumentCount++;
}
}
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
val = atoi(++ptr);
val = atoi(ptr);
if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
mac->auxChannelIndex = val;
validArgumentCount++;
@ -1257,20 +1265,20 @@ static void cliSerial(char *cmdline)
validArgumentCount++;
}
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
val = atoi(++ptr);
val = atoi(ptr);
portConfig.functionMask = val & 0xFFFF;
validArgumentCount++;
}
for (i = 0; i < 4; i ++) {
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (!ptr) {
break;
}
val = atoi(++ptr);
val = atoi(ptr);
uint8_t baudRateIndex = lookupBaudRateIndex(val);
if (baudRates[baudRateIndex] != (uint32_t) val) {
@ -1437,17 +1445,17 @@ static void cliAdjustmentRange(char *cmdline)
adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
uint8_t validArgumentCount = 0;
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
val = atoi(++ptr);
val = atoi(ptr);
if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
ar->adjustmentIndex = val;
validArgumentCount++;
}
}
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
val = atoi(++ptr);
val = atoi(ptr);
if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
ar->auxChannelIndex = val;
validArgumentCount++;
@ -1456,17 +1464,17 @@ static void cliAdjustmentRange(char *cmdline)
ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
val = atoi(++ptr);
val = atoi(ptr);
if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
ar->adjustmentFunction = val;
validArgumentCount++;
}
}
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
val = atoi(++ptr);
val = atoi(ptr);
if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
ar->auxSwitchChannelIndex = val;
validArgumentCount++;
@ -1534,9 +1542,9 @@ static void cliMotorMix(char *cmdline)
for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++)
masterConfig.customMotorMixer[i].throttle = 0.0f;
} else if (strncasecmp(cmdline, "load", 4) == 0) {
ptr = strchr(cmdline, ' ');
ptr = nextArg(cmdline);
if (ptr) {
len = strlen(++ptr);
len = strlen(ptr);
for (uint32_t i = 0; ; i++) {
if (mixerNames[i] == NULL) {
cliPrint("Invalid name\r\n");
@ -1554,30 +1562,30 @@ static void cliMotorMix(char *cmdline)
ptr = cmdline;
uint32_t i = atoi(ptr); // get motor number
if (i < MAX_SUPPORTED_MOTORS) {
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
masterConfig.customMotorMixer[i].throttle = fastA2F(++ptr);
masterConfig.customMotorMixer[i].throttle = fastA2F(ptr);
check++;
}
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
masterConfig.customMotorMixer[i].roll = fastA2F(++ptr);
masterConfig.customMotorMixer[i].roll = fastA2F(ptr);
check++;
}
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
masterConfig.customMotorMixer[i].pitch = fastA2F(++ptr);
masterConfig.customMotorMixer[i].pitch = fastA2F(ptr);
check++;
}
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
masterConfig.customMotorMixer[i].yaw = fastA2F(++ptr);
masterConfig.customMotorMixer[i].yaw = fastA2F(ptr);
check++;
}
if (check != 4) {
cliShowParseError();
} else {
cliMotorMix("");
printMotorMix(DUMP_MASTER, NULL);
}
} else {
cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
@ -1625,15 +1633,15 @@ static void cliRxRange(char *cmdline)
if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
int rangeMin, rangeMax;
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
rangeMin = atoi(++ptr);
rangeMin = atoi(ptr);
validArgumentCount++;
}
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
rangeMax = atoi(++ptr);
rangeMax = atoi(ptr);
validArgumentCount++;
}
@ -1683,8 +1691,8 @@ static void cliLed(char *cmdline)
ptr = cmdline;
i = atoi(ptr);
if (i < LED_MAX_STRIP_LENGTH) {
ptr = strchr(cmdline, ' ');
if (!parseLedStripConfig(i, ++ptr)) {
ptr = nextArg(cmdline);
if (!parseLedStripConfig(i, ptr)) {
cliShowParseError();
}
} else {
@ -1731,8 +1739,8 @@ static void cliColor(char *cmdline)
ptr = cmdline;
i = atoi(ptr);
if (i < LED_CONFIGURABLE_COLOR_COUNT) {
ptr = strchr(cmdline, ' ');
if (!parseColor(i, ++ptr)) {
ptr = nextArg(cmdline);
if (!parseColor(i, ptr)) {
cliShowParseError();
}
} else {
@ -1985,9 +1993,9 @@ static void cliServoMix(char *cmdline)
masterConfig.servoConf[i].reversedSources = 0;
}
} else if (strncasecmp(cmdline, "load", 4) == 0) {
ptr = strchr(cmdline, ' ');
ptr = nextArg(cmdline);
if (ptr) {
len = strlen(++ptr);
len = strlen(ptr);
for (uint32_t i = 0; ; i++) {
if (mixerNames[i] == NULL) {
cliPrintf("Invalid name\r\n");
@ -2283,25 +2291,25 @@ static void cliVtx(char *cmdline)
if (i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT) {
vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i];
uint8_t validArgumentCount = 0;
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
val = atoi(++ptr);
val = atoi(ptr);
if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
cac->auxChannelIndex = val;
validArgumentCount++;
}
}
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
val = atoi(++ptr);
val = atoi(ptr);
if (val >= VTX_BAND_MIN && val <= VTX_BAND_MAX) {
cac->band = val;
validArgumentCount++;
}
}
ptr = strchr(ptr, ' ');
ptr = nextArg(ptr);
if (ptr) {
val = atoi(++ptr);
val = atoi(ptr);
if (val >= VTX_CHANNEL_MIN && val <= VTX_CHANNEL_MAX) {
cac->channel = val;
validArgumentCount++;

View File

@ -603,7 +603,8 @@ static uint32_t packFlightModeFlags(void)
IS_ENABLED(ARMING_FLAG(ARMED)) << BOXARM |
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX |
IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << BOXFAILSAFE |
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAIRMODE)) << BOXAIRMODE;
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAIRMODE)) << BOXAIRMODE |
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX)) << BOXFPVANGLEMIX;
for (i = 0; i < activeBoxIdCount; i++) {
int flag = (tmp & (1 << activeBoxIds[i]));
@ -1274,10 +1275,10 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize16(currentProfile->pidProfile.yaw_p_limit);
serialize8(currentProfile->pidProfile.deltaMethod);
serialize8(currentProfile->pidProfile.vbatPidCompensation);
serialize8(currentProfile->pidProfile.ptermSetpointWeight);
serialize8(currentProfile->pidProfile.ptermSRateWeight);
serialize8(currentProfile->pidProfile.dtermSetpointWeight);
serialize8(currentProfile->pidProfile.toleranceBand);
serialize8(currentProfile->pidProfile.toleranceBandReduction);
serialize8(0); // reserved
serialize8(0); // reserved
serialize8(currentProfile->pidProfile.itermThrottleGain);
serialize16(currentProfile->pidProfile.rateAccelLimit);
serialize16(currentProfile->pidProfile.yawRateAccelLimit);
@ -1876,10 +1877,10 @@ static bool processInCommand(void)
currentProfile->pidProfile.yaw_p_limit = read16();
currentProfile->pidProfile.deltaMethod = read8();
currentProfile->pidProfile.vbatPidCompensation = read8();
currentProfile->pidProfile.ptermSetpointWeight = read8();
currentProfile->pidProfile.ptermSRateWeight = read8();
currentProfile->pidProfile.dtermSetpointWeight = read8();
currentProfile->pidProfile.toleranceBand = read8();
currentProfile->pidProfile.toleranceBandReduction = read8();
read8(); // reserved
read8(); // reserved
currentProfile->pidProfile.itermThrottleGain = read8();
currentProfile->pidProfile.rateAccelLimit = read16();
currentProfile->pidProfile.yawRateAccelLimit = read16();

View File

@ -159,7 +159,6 @@ void gyroUpdate(void)
}
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
if (debugMode == DEBUG_GYRO) debug[axis] = gyroADC[axis];
gyroADC[axis] = gyroADCRaw[axis];
}
@ -173,21 +172,21 @@ void gyroUpdate(void)
if (gyroSoftLpfHz) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
float sample = (float) gyroADC[axis];
if (gyroSoftNotchHz) {
sample = biquadFilterApply(&gyroFilterNotch[axis], sample);
}
if (debugMode == DEBUG_NOTCH && axis < 2){
debug[axis*2 + 0] = gyroADC[axis];
debug[axis*2 + 1] = lrintf(sample);
}
if (debugMode == DEBUG_GYRO)
debug[axis] = gyroADC[axis];
if (gyroSoftLpfType == FILTER_BIQUAD)
gyroADCf[axis] = biquadFilterApply(&gyroFilterLPF[axis], (float) gyroADC[axis]);
else
gyroADCf[axis] = pt1FilterApply4(&gyroFilterPt1[axis], (float) gyroADC[axis], gyroSoftLpfHz, gyroDt);
if (debugMode == DEBUG_NOTCH)
debug[axis] = lrintf(gyroADCf[axis]);
if (gyroSoftNotchHz)
gyroADCf[axis] = biquadFilterApply(&gyroFilterNotch[axis], gyroADCf[axis]);
if (gyroSoftLpfType == FILTER_BIQUAD) {
gyroADCf[axis] = biquadFilterApply(&gyroFilterLPF[axis], sample);
} else {
gyroADCf[axis] = pt1FilterApply4(&gyroFilterPt1[axis], sample, gyroSoftLpfHz, gyroDt);
}
gyroADC[axis] = lrintf(gyroADCf[axis]);
}
} else {

View File

@ -444,7 +444,14 @@ static bool detectBaro(baroSensor_e baroHardwareToUse)
switch (baroHardware) {
case BARO_DEFAULT:
; // fallthough
case BARO_BMP085:
#ifdef USE_BARO_BMP085
if (bmp085Detect(bmp085Config, &baro)) {
baroHardware = BARO_BMP085;
break;
}
#endif
; // fallthough
case BARO_MS5611:
#ifdef USE_BARO_MS5611
if (ms5611Detect(&baro)) {
@ -453,14 +460,6 @@ static bool detectBaro(baroSensor_e baroHardwareToUse)
}
#endif
; // fallthough
case BARO_BMP085:
#ifdef USE_BARO_BMP085
if (bmp085Detect(bmp085Config, &baro)) {
baroHardware = BARO_BMP085;
break;
}
#endif
; // fallthough
case BARO_BMP280:
#ifdef USE_BARO_BMP280
if (bmp280Detect(&baro)) {
@ -468,6 +467,7 @@ static bool detectBaro(baroSensor_e baroHardwareToUse)
break;
}
#endif
; // fallthough
case BARO_NONE:
baroHardware = BARO_NONE;
break;

View File

@ -0,0 +1,52 @@
# AlienFlight (ALIENFLIGHTF1, ALIENFLIGHTF3 and ALIENFLIGHTF4 target)
AlienWii is now AlienFlight. This targets supports various variants of brushed and brushless flight controllers. The designs for them are released partially for public use at:
http://www.alienflight.com
All published designs are flight tested by various people. The intention here is to make these flight controllers available and enable skilled users or RC vendors to build this designs.
Some variants of the AlienFlight controllers will be available for purchase from:
http://www.microfpv.eu
Here are the general hardware specifications for this boards:
- STM32F103CBT6 MCU (ALIENFLIGHTF1)
- STM32F303CCT6 MCU (ALIENFLIGHTF3)
- STM32F405RGT6 MCU (ALIENFLIGHTF4)
- MPU6050/6500/9250/ICM-20608-G accelerometer/gyro(/mag) sensor unit
- The MPU sensor interrupt is connected to the MCU for all new F3 and F4 designs and enabled in the firmware
- 4-8 x 4.2A to 9.5A brushed ESCs, integrated, to run the strongest micro motors (brushed variants)
- extra-wide traces on the PCB, for maximum power throughput (brushed variants)
- some new F4 boards using a 4-layer PCB for better power distribution
- USB port, integrated
- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100, Lemon RX or Deltang Rx31) and SBUS
- CPPM input
- ground and 3.3V for the receiver, some boards have also the option to power an 5V receiver
- hardware bind plug for easy binding
- motor connections are at the corners for a clean look with reduced wiring
- small footprint
- direct operation from a single cell Lipoly battery for brushed versions
- 3.3V LDO power regulator (older prototypes)
- 3.3V buck-boost power converter (all new versions)
- 5V buck-boost power converter for FPV (some versions)
- brushless versions are designed for 3S operation and also have an 5V power output
- battery monitoring with an LED for buzzer functionality (for some ALIENFLIGHTF3 and F4 variants only)
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator.
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
set spektrum_sat_bind = 5
For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document.
Deltang receivers in serial mode will work like any other Spektrum satellite receiver (10bit, 22ms) only the bind process will be different.
The pin layout for the ALIENFLIGHTF1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The hardware bind pin is connected to pin 41 (PB5). The pin layout for the ALIENFLIGHTF3 is similar to Sparky. The hardware bind pin is connected to pin 25 (PB12). The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight/AlienWii F3 layouts running the same firmware which takes care on the differences with a hardware detection.
The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3 or ALIENFLIGHTF4. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator.
## Flashing the firmware
The firmware can be updated with the BetaFlight configurator as for any other target. All AlienFlight boards have a boot jumper which need to be closed for initial flashing or for recovery from a broken firmware.

View File

@ -18,6 +18,7 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFF1" // AlienFlight F1.
#define TARGET_CONFIG
#define LED0 PB3
#define LED1 PB4
@ -25,7 +26,6 @@
#define BEEPER PA12
#define USE_EXTI
#define MAG_INT_EXTI PC14
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
@ -70,8 +70,9 @@
// USART2, PA3
#define BIND_PIN PA3
// alternative defaults for AlienFlight F1 target
#define TARGET_CONFIG
#define HARDWARE_BIND_PLUG
// Hardware bind plug at PB5 (Pin 41)
#define BINDPLUG_PIN PB5
#define BRUSHED_MOTORS
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
@ -80,10 +81,7 @@
#define SERIALRX_UART SERIAL_PORT_USART2
#define RX_CHANNELS_TAER
#define HARDWARE_BIND_PLUG
// Hardware bind plug at PB5 (Pin 41)
#define BINDPLUG_PIN PB5
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - assuming all IOs on 48pin package
#define TARGET_IO_PORTA 0xffff

View File

@ -0,0 +1,52 @@
# AlienFlight (ALIENFLIGHTF1, ALIENFLIGHTF3 and ALIENFLIGHTF4 target)
AlienWii is now AlienFlight. This targets supports various variants of brushed and brushless flight controllers. The designs for them are released partially for public use at:
http://www.alienflight.com
All published designs are flight tested by various people. The intention here is to make these flight controllers available and enable skilled users or RC vendors to build this designs.
Some variants of the AlienFlight controllers will be available for purchase from:
http://www.microfpv.eu
Here are the general hardware specifications for this boards:
- STM32F103CBT6 MCU (ALIENFLIGHTF1)
- STM32F303CCT6 MCU (ALIENFLIGHTF3)
- STM32F405RGT6 MCU (ALIENFLIGHTF4)
- MPU6050/6500/9250/ICM-20608-G accelerometer/gyro(/mag) sensor unit
- The MPU sensor interrupt is connected to the MCU for all new F3 and F4 designs and enabled in the firmware
- 4-8 x 4.2A to 9.5A brushed ESCs, integrated, to run the strongest micro motors (brushed variants)
- extra-wide traces on the PCB, for maximum power throughput (brushed variants)
- some new F4 boards using a 4-layer PCB for better power distribution
- USB port, integrated
- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100, Lemon RX or Deltang Rx31) and SBUS
- CPPM input
- ground and 3.3V for the receiver, some boards have also the option to power an 5V receiver
- hardware bind plug for easy binding
- motor connections are at the corners for a clean look with reduced wiring
- small footprint
- direct operation from a single cell Lipoly battery for brushed versions
- 3.3V LDO power regulator (older prototypes)
- 3.3V buck-boost power converter (all new versions)
- 5V buck-boost power converter for FPV (some versions)
- brushless versions are designed for 3S operation and also have an 5V power output
- battery monitoring with an LED for buzzer functionality (for some ALIENFLIGHTF3 and F4 variants only)
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator.
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
set spektrum_sat_bind = 5
For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document.
Deltang receivers in serial mode will work like any other Spektrum satellite receiver (10bit, 22ms) only the bind process will be different.
The pin layout for the ALIENFLIGHTF1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The hardware bind pin is connected to pin 41 (PB5). The pin layout for the ALIENFLIGHTF3 is similar to Sparky. The hardware bind pin is connected to pin 25 (PB12). The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight/AlienWii F3 layouts running the same firmware which takes care on the differences with a hardware detection.
The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3 or ALIENFLIGHTF4. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator.
## Flashing the firmware
The firmware can be updated with the BetaFlight configurator as for any other target. All AlienFlight boards have a boot jumper which need to be closed for initial flashing or for recovery from a broken firmware.

View File

@ -122,11 +122,10 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - assuming 303 in 64pin package, TODO
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 11

View File

@ -0,0 +1,52 @@
# AlienFlight (ALIENFLIGHTF1, ALIENFLIGHTF3 and ALIENFLIGHTF4 target)
AlienWii is now AlienFlight. This targets supports various variants of brushed and brushless flight controllers. The designs for them are released partially for public use at:
http://www.alienflight.com
All published designs are flight tested by various people. The intention here is to make these flight controllers available and enable skilled users or RC vendors to build this designs.
Some variants of the AlienFlight controllers will be available for purchase from:
http://www.microfpv.eu
Here are the general hardware specifications for this boards:
- STM32F103CBT6 MCU (ALIENFLIGHTF1)
- STM32F303CCT6 MCU (ALIENFLIGHTF3)
- STM32F405RGT6 MCU (ALIENFLIGHTF4)
- MPU6050/6500/9250/ICM-20608-G accelerometer/gyro(/mag) sensor unit
- The MPU sensor interrupt is connected to the MCU for all new F3 and F4 designs and enabled in the firmware
- 4-8 x 4.2A to 9.5A brushed ESCs, integrated, to run the strongest micro motors (brushed variants)
- extra-wide traces on the PCB, for maximum power throughput (brushed variants)
- some new F4 boards using a 4-layer PCB for better power distribution
- USB port, integrated
- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100, Lemon RX or Deltang Rx31) and SBUS
- CPPM input
- ground and 3.3V for the receiver, some boards have also the option to power an 5V receiver
- hardware bind plug for easy binding
- motor connections are at the corners for a clean look with reduced wiring
- small footprint
- direct operation from a single cell Lipoly battery for brushed versions
- 3.3V LDO power regulator (older prototypes)
- 3.3V buck-boost power converter (all new versions)
- 5V buck-boost power converter for FPV (some versions)
- brushless versions are designed for 3S operation and also have an 5V power output
- battery monitoring with an LED for buzzer functionality (for some ALIENFLIGHTF3 and F4 variants only)
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator.
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
set spektrum_sat_bind = 5
For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document.
Deltang receivers in serial mode will work like any other Spektrum satellite receiver (10bit, 22ms) only the bind process will be different.
The pin layout for the ALIENFLIGHTF1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The hardware bind pin is connected to pin 41 (PB5). The pin layout for the ALIENFLIGHTF3 is similar to Sparky. The hardware bind pin is connected to pin 25 (PB12). The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight/AlienWii F3 layouts running the same firmware which takes care on the differences with a hardware detection.
The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3 or ALIENFLIGHTF4. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator.
## Flashing the firmware
The firmware can be updated with the BetaFlight configurator as for any other target. All AlienFlight boards have a boot jumper which need to be closed for initial flashing or for recovery from a broken firmware.

View File

@ -27,6 +27,7 @@
#define LED1 PD2
#define BEEPER PC13
#define BEEPER_INVERTED
#define INVERTER PC15
#define INVERTER_USART USART2

View File

@ -0,0 +1,13 @@
==BETAFLIGHTF3==
Owner: BorisB
Board information:
- CPU - STM32F303CCT6
- MPU-6000
- SD Card Slot
- Build in 5V BEC + LC filter - board can be powered from main battery
- Built in current meter, PDB
More info to come

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/>.
*/
//Target code By Hector "Hectech FPV" Hind
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_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),
0xFFFF
};
const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PB7), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
{ 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
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB9
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 - PA1
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
};

View File

@ -0,0 +1,151 @@
/*
* 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/>.
*/
//Target code By Hector "Hectech FPV" Hind
#pragma once
#define TARGET_BOARD_IDENTIFIER "BETAFC"
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
//#define LED0 PC14
#define BEEPER PC15
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
#define MPU6000_CS_PIN PA15
#define MPU6000_SPI_INSTANCE SPI1
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
// MPU6000 interrupts
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled)
#define MPU_INT_EXTI PC13
#define USE_EXTI
#define USB_IO
//#define USE_FLASHFS
//#define USE_FLASH_M25P16
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 5
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA2 // PA14 / SWCLK
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define SOFTSERIAL_2_TIMER TIM3
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 5
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 6
#undef USE_I2C
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
//GPIO_AF_1
#define SPI1_NSS_PIN PA15
#define SPI1_SCK_PIN PB3
#define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI2
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
//#define SDCARD_SPI_CS_GPIO SPI2_GPIO
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
//#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
//#define SDCARD_DMA_CHANNEL DMA_Channel_0
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
#define WS2811_PIN PA8
#define WS2811_TIMER TIM1
#define WS2811_DMA_CHANNEL DMA1_Channel2
#define WS2811_IRQ DMA1_Channel2_IRQn
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_CURRENT_METER)
#define SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )

View File

@ -0,0 +1,17 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
TARGET_FLAGS = -DSPRACINGF3
TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/accgyro_spi_mpu6000.c \
drivers/compass_ak8975.c \
drivers/compass_hmc5883l.c \
drivers/display_ug2864hsweg01.h \
drivers/flash_m25p16.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f30x.c \
drivers/serial_softserial.c \
drivers/sonar_hcsr04.c

View File

@ -0,0 +1,25 @@
##RACABASE FC
Owner: Marcin Baliniak (marcin <at> baliniak.pl)
Available at: shop.rotoracer.com
###Board information:
- CPU - STM32F303CCT6
- MPU-6000 - connected to SPI2
- SPI Flash - connected to SPI2
- MAX7456 - connected to SPI2 (NO DMA)
- Build in 5V BEC + LC filter - board can be powered from main battery
- Input voltage: 5V - 17.4V
- RC input: PPM, S.BUS (build in inverter) - Uart2, Spectrum-Uart3
- Other connectors: RSSI, Current sensor, LED strip, Buzzer, Video IN/Out + LC filter
- Weight: 6 g
- Size: 36 mm x 36 mm x 5 mm
###Photo
![Board photo](https://cdn.shoplo.com/0639/products/th1024/aaaw/838-rr_flight_controller_rotoracer_fc_rotoracer_racebase.jpg)
###Port description
![Port description](https://cdn.shoplo.com/0639/products/th1024/aaaw/844-racebase-render-en.png)

View File

@ -0,0 +1,83 @@
/*
* 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(master_t *config) {
config->rxConfig.sbus_inversion = 0;
config->rxConfig.rssi_scale = 19;
config->rxConfig.serialrx_provider = SERIALRX_SBUS;
}

View File

@ -0,0 +1,24 @@
==RACABASE FC==
Owner: Marcin Baliniak (marcin <at> baliniak.pl)
Available at: shop.rotoracer.com
Board information:
- CPU - STM32F303CCT6
- MPU-6000 - connected to SPI2
- SPI Flash - connected to SPI2
- MAX7456 - connected to SPI2 (NO DMA)
- Build in 5V BEC + LC filter - board can be powered from main battery
- Input voltage: 5V - 17.4V
- RC input: PPM, S.BUS (build in inverter) - Uart2, Spectrum-Uart3
- Other connectors: RSSI, Current sensor, LED strip, Buzzer, Video IN/Out + LC filter
- Weight: 6 g
- Size: 36 mm x 36 mm x 5 mm
Photo:
https://cdn.shoplo.com/0639/products/th1024/aaaw/838-rr_flight_controller_rotoracer_fc_rotoracer_racebase.jpg
Port description:
https://cdn.shoplo.com/0639/products/th1024/aaaw/844-racebase-render-en.png

View File

@ -0,0 +1,59 @@
/*
* 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"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t airPPM[] = {
0xFFFF
};
const uint16_t airPWM[] = {
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1},
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM2 - PC6
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM3 - PC7
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PMW4 - PC8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM5 - PC9
};

124
src/main/target/RACEBASE/target.h Executable file
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 "RBFC"
#define TARGET_CONFIG
#define LED0 PB3
#define LED0_INVERTED
#define LED1 PB4
#define LED1_INVERTED
#define BEEPER PA12
#define BEEPER_INVERTED
#define USE_EXTI
#define MPU_INT_EXTI PC5
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define MPU6000_CS_PIN PB5
#define MPU6000_SPI_INSTANCE SPI2
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW90_DEG
#define GYRO_MPU6000_ALIGN CW90_DEG
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT 3
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define SERIALRX_UART SERIAL_PORT_USART2
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI2
#define MAX7456_SPI_CS_PIN PA7
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define M25P16_SPI_SHARED
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PA6
#define LED_STRIP
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
#define WS2811_PIN PA8
#define WS2811_TIMER TIM1
#define WS2811_DMA_CHANNEL DMA1_Channel2
#define WS2811_IRQ DMA1_Channel2_IRQn
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
#define OSD
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define USE_SERVOS
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_VBAT | FEATURE_RSSI_ADC)
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(5))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 5
#define USED_TIMERS (TIM_N(2) | TIM_N(4))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM4)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)

View File

@ -0,0 +1,12 @@
F3_TARGETS += $(TARGET)
FEATURES = ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/accgyro_spi_mpu6000.c \
drivers/flash_m25p16.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f30x.c \
drivers/max7456.c \
io/osd.c

View File

@ -30,6 +30,8 @@
#define LED2 PB6
#define BEEPER PC9
#define BEEPER_INVERTED
#define INVERTER PC6
#define INVERTER_USART USART6