Revert "Merge pull request #372 from aughey/betaflight"

This reverts commit a6a5f50ffb, reversing
changes made to 9cc5503851.
This commit is contained in:
borisbstyle 2016-05-04 00:00:04 +02:00
parent a6a5f50ffb
commit 5ffb3b5068
6 changed files with 30 additions and 58 deletions

View File

@ -111,6 +111,26 @@ int32_t applyDeadband(int32_t value, int32_t deadband)
return value; return value;
} }
inline int constrain(int amt, int low, int high)
{
if (amt < low)
return low;
else if (amt > high)
return high;
else
return amt;
}
inline float constrainf(float amt, float low, float high)
{
if (amt < low)
return low;
else if (amt > high)
return high;
else
return amt;
}
void devClear(stdev_t *dev) void devClear(stdev_t *dev)
{ {
dev->m_n = 0; dev->m_n = 0;

View File

@ -116,25 +116,3 @@ void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count);
int16_t qPercent(fix12_t q); int16_t qPercent(fix12_t q);
int16_t qMultiply(fix12_t q, int16_t input); int16_t qMultiply(fix12_t q, int16_t input);
fix12_t qConstruct(int16_t num, int16_t den); fix12_t qConstruct(int16_t num, int16_t den);
// Defining constrain and constrainf as inline in the include file
// because these functions are used universally and should be fast.
inline int constrain(int amt, int low, int high)
{
if (amt < low)
return low;
else if (amt > high)
return high;
else
return amt;
}
inline float constrainf(float amt, float low, float high)
{
if (amt < low)
return low;
else if (amt > high)
return high;
else
return amt;
}

View File

@ -124,15 +124,8 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
#define FLASH_TO_RESERVE_FOR_CONFIG 0x1000 #define FLASH_TO_RESERVE_FOR_CONFIG 0x1000
#endif #endif
// use the last flash pages for storage
#ifdef CUSTOM_FLASH_MEMORY_ADDRESS
size_t custom_flash_memory_address = 0;
#define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address)
#else
// use the last flash pages for storage // use the last flash pages for storage
#define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG)) #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
#endif
master_t masterConfig; // master config struct with data independent from profiles master_t masterConfig; // master config struct with data independent from profiles
profile_t *currentProfile; profile_t *currentProfile;

View File

@ -753,11 +753,6 @@ void mixTable(void)
uint32_t i; uint32_t i;
fix12_t vbatCompensationFactor; fix12_t vbatCompensationFactor;
static fix12_t mixReduction; static fix12_t mixReduction;
bool use_vbat_compensation = false;
if (batteryConfig && batteryConfig->vbatPidCompensation) {
use_vbat_compensation = true;
vbatCompensationFactor = calculateVbatPidCompensation();
}
bool isFailsafeActive = failsafeIsActive(); // TODO - Find out if failsafe checks are really needed here in mixer code bool isFailsafeActive = failsafeIsActive(); // TODO - Find out if failsafe checks are really needed here in mixer code
@ -771,6 +766,8 @@ void mixTable(void)
int16_t rollPitchYawMixMax = 0; // assumption: symetrical about zero. int16_t rollPitchYawMixMax = 0; // assumption: symetrical about zero.
int16_t rollPitchYawMixMin = 0; int16_t rollPitchYawMixMin = 0;
if (batteryConfig->vbatPidCompensation) vbatCompensationFactor = calculateVbatPidCompensation(); // Calculate voltage compensation
// Find roll/pitch/yaw desired output // Find roll/pitch/yaw desired output
for (i = 0; i < motorCount; i++) { for (i = 0; i < motorCount; i++) {
rollPitchYawMix[i] = rollPitchYawMix[i] =
@ -778,7 +775,7 @@ void mixTable(void)
axisPID[ROLL] * currentMixer[i].roll + axisPID[ROLL] * currentMixer[i].roll +
-mixerConfig->yaw_motor_direction * axisPID[YAW] * currentMixer[i].yaw; -mixerConfig->yaw_motor_direction * axisPID[YAW] * currentMixer[i].yaw;
if (use_vbat_compensation) rollPitchYawMix[i] = qMultiply(vbatCompensationFactor, rollPitchYawMix[i]); // Add voltage compensation if (batteryConfig->vbatPidCompensation) rollPitchYawMix[i] = qMultiply(vbatCompensationFactor, rollPitchYawMix[i]); // Add voltage compensation
if (rollPitchYawMix[i] > rollPitchYawMixMax) rollPitchYawMixMax = rollPitchYawMix[i]; if (rollPitchYawMix[i] > rollPitchYawMixMax) rollPitchYawMixMax = rollPitchYawMix[i];
if (rollPitchYawMix[i] < rollPitchYawMixMin) rollPitchYawMixMin = rollPitchYawMix[i]; if (rollPitchYawMix[i] < rollPitchYawMixMin) rollPitchYawMixMin = rollPitchYawMix[i];

View File

@ -26,6 +26,7 @@
#include "common/axis.h" #include "common/axis.h"
#include "common/color.h" #include "common/color.h"
#include "common/atomic.h"
#include "common/maths.h" #include "common/maths.h"
#include "drivers/nvic.h" #include "drivers/nvic.h"
@ -657,7 +658,7 @@ void processLoopback(void) {
#define processLoopback() #define processLoopback()
#endif #endif
void main_init(void) { int main(void) {
init(); init();
/* Setup scheduler */ /* Setup scheduler */
@ -728,22 +729,12 @@ void main_init(void) {
#ifdef USE_BST #ifdef USE_BST
setTaskEnabled(TASK_BST_MASTER_PROCESS, true); setTaskEnabled(TASK_BST_MASTER_PROCESS, true);
#endif #endif
}
void main_step(void) { while (1) {
scheduler(); scheduler();
processLoopback(); processLoopback();
} }
#ifndef NOMAIN
int main(void)
{
main_init();
while(1) {
main_step();
} }
}
#endif
#ifdef DEBUG_HARDFAULTS #ifdef DEBUG_HARDFAULTS
//from: https://mcuoneclipse.com/2012/11/24/debugging-hard-faults-on-arm-cortex-m/ //from: https://mcuoneclipse.com/2012/11/24/debugging-hard-faults-on-arm-cortex-m/

View File

@ -214,7 +214,6 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
} }
#ifdef USE_FAKE_GYRO #ifdef USE_FAKE_GYRO
int16_t fake_gyro_values[XYZ_AXIS_COUNT] = { 0,0,0 };
static void fakeGyroInit(uint16_t lpf) static void fakeGyroInit(uint16_t lpf)
{ {
UNUSED(lpf); UNUSED(lpf);
@ -222,9 +221,7 @@ static void fakeGyroInit(uint16_t lpf)
static bool fakeGyroRead(int16_t *gyroADC) static bool fakeGyroRead(int16_t *gyroADC)
{ {
for (int i = 0; i < XYZ_AXIS_COUNT; ++i) { memset(gyroADC, 0, sizeof(int16_t[XYZ_AXIS_COUNT]));
gyroADC[i] = fake_gyro_values[i];
}
return true; return true;
} }
@ -244,13 +241,9 @@ bool fakeGyroDetect(gyro_t *gyro)
#endif #endif
#ifdef USE_FAKE_ACC #ifdef USE_FAKE_ACC
int16_t fake_acc_values[XYZ_AXIS_COUNT] = {0,0,0};
static void fakeAccInit(void) {} static void fakeAccInit(void) {}
static bool fakeAccRead(int16_t *accData) { static bool fakeAccRead(int16_t *accData) {
for(int i=0;i<XYZ_AXIS_COUNT;++i) { memset(accData, 0, sizeof(int16_t[XYZ_AXIS_COUNT]));
accData[i] = fake_acc_values[i];
}
return true; return true;
} }