1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-18 22:05:17 +03:00

Add fast RAM support, CCM or TCM depending on processor

This commit is contained in:
Martin Budden 2017-12-14 22:23:34 +00:00
parent 5892cac45d
commit a33a82725e
24 changed files with 105 additions and 59 deletions

View file

@ -108,10 +108,10 @@ PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, customMotorMixer, PG_MOTOR
#define TRICOPTER_ERROR_RATE_YAW_SATURATED 75 // rate at which tricopter yaw axis becomes saturated, determined experimentally by TriFlight
static uint8_t motorCount;
static float motorMixRange;
static FAST_RAM uint8_t motorCount;
static FAST_RAM float motorMixRange;
float motor[MAX_SUPPORTED_MOTORS];
float FAST_RAM motor[MAX_SUPPORTED_MOTORS];
float motor_disarmed[MAX_SUPPORTED_MOTORS];
mixerMode_e currentMixerMode;
@ -306,12 +306,12 @@ const mixer_t mixers[] = {
};
#endif // !USE_QUAD_MIXER_ONLY
float motorOutputHigh, motorOutputLow;
FAST_RAM float motorOutputHigh, motorOutputLow;
static float disarmMotorOutput, deadbandMotor3dHigh, deadbandMotor3dLow;
static uint16_t rcCommand3dDeadBandLow;
static uint16_t rcCommand3dDeadBandHigh;
static float rcCommandThrottleRange, rcCommandThrottleRange3dLow, rcCommandThrottleRange3dHigh;
static FAST_RAM float disarmMotorOutput, deadbandMotor3dHigh, deadbandMotor3dLow;
static FAST_RAM uint16_t rcCommand3dDeadBandLow;
static FAST_RAM uint16_t rcCommand3dDeadBandHigh;
static FAST_RAM float rcCommandThrottleRange, rcCommandThrottleRange3dLow, rcCommandThrottleRange3dHigh;
uint8_t getMotorCount(void)
{
@ -513,12 +513,12 @@ void stopPwmAllMotors(void)
delayMicroseconds(1500);
}
static float throttle = 0;
static float motorOutputMin;
static float motorRangeMin;
static float motorRangeMax;
static float motorOutputRange;
static int8_t motorOutputMixSign;
static FAST_RAM float throttle = 0;
static FAST_RAM float motorOutputMin;
static FAST_RAM float motorRangeMin;
static FAST_RAM float motorRangeMax;
static FAST_RAM float motorOutputRange;
static FAST_RAM int8_t motorOutputMixSign;
static FAST_CODE void calculateThrottleAndCurrentMotorEndpoints(timeUs_t currentTimeUs)
{

View file

@ -51,14 +51,14 @@
#include "sensors/gyro.h"
#include "sensors/acceleration.h"
uint32_t targetPidLooptime;
static bool pidStabilisationEnabled;
FAST_RAM uint32_t targetPidLooptime;
static FAST_RAM bool pidStabilisationEnabled;
static bool inCrashRecoveryMode = false;
static FAST_RAM bool inCrashRecoveryMode = false;
float axisPID_P[3], axisPID_I[3], axisPID_D[3];
FAST_RAM float axisPID_P[3], axisPID_I[3], axisPID_D[3];
static float dT;
static FAST_RAM float dT;
PG_REGISTER_WITH_RESET_TEMPLATE(pidConfig_t, pidConfig, PG_PID_CONFIG, 1);
@ -143,7 +143,7 @@ void pidResetITerm(void)
}
}
static float itermAccelerator = 1.0f;
static FAST_RAM float itermAccelerator = 1.0f;
void pidSetItermAccelerator(float newItermAccelerator)
{
@ -157,12 +157,12 @@ void pidStabilisationState(pidStabilisationState_e pidControllerState)
const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
static filterApplyFnPtr dtermNotchFilterApplyFn;
static void *dtermFilterNotch[2];
static filterApplyFnPtr dtermLpfApplyFn;
static void *dtermFilterLpf[2];
static filterApplyFnPtr ptermYawFilterApplyFn;
static void *ptermYawFilter;
static FAST_RAM filterApplyFnPtr dtermNotchFilterApplyFn;
static FAST_RAM void *dtermFilterNotch[2];
static FAST_RAM filterApplyFnPtr dtermLpfApplyFn;
static FAST_RAM void *dtermFilterLpf[2];
static FAST_RAM filterApplyFnPtr ptermYawFilterApplyFn;
static FAST_RAM void *ptermYawFilter;
typedef union dtermFilterLpf_u {
pt1Filter_t pt1Filter[2];
@ -249,22 +249,22 @@ void pidInitFilters(const pidProfile_t *pidProfile)
}
}
static float Kp[3], Ki[3], Kd[3];
static float maxVelocity[3];
static float relaxFactor;
static float dtermSetpointWeight;
static float levelGain, horizonGain, horizonTransition, horizonCutoffDegrees, horizonFactorRatio;
static float ITermWindupPointInv;
static uint8_t horizonTiltExpertMode;
static timeDelta_t crashTimeLimitUs;
static timeDelta_t crashTimeDelayUs;
static int32_t crashRecoveryAngleDeciDegrees;
static float crashRecoveryRate;
static float crashDtermThreshold;
static float crashGyroThreshold;
static float crashSetpointThreshold;
static float crashLimitYaw;
static float itermLimit;
static FAST_RAM float Kp[3], Ki[3], Kd[3];
static FAST_RAM float maxVelocity[3];
static FAST_RAM float relaxFactor;
static FAST_RAM float dtermSetpointWeight;
static FAST_RAM float levelGain, horizonGain, horizonTransition, horizonCutoffDegrees, horizonFactorRatio;
static FAST_RAM float ITermWindupPointInv;
static FAST_RAM uint8_t horizonTiltExpertMode;
static FAST_RAM timeDelta_t crashTimeLimitUs;
static FAST_RAM timeDelta_t crashTimeDelayUs;
static FAST_RAM int32_t crashRecoveryAngleDeciDegrees;
static FAST_RAM float crashRecoveryRate;
static FAST_RAM float crashDtermThreshold;
static FAST_RAM float crashGyroThreshold;
static FAST_RAM float crashSetpointThreshold;
static FAST_RAM float crashLimitYaw;
static FAST_RAM float itermLimit;
void pidInitConfig(const pidProfile_t *pidProfile)
{

View file

@ -42,21 +42,21 @@
// 2 - time spent in scheduler
// 3 - time spent executing check function
static cfTask_t *currentTask = NULL;
static FAST_RAM cfTask_t *currentTask = NULL;
static uint32_t totalWaitingTasks;
static uint32_t totalWaitingTasksSamples;
static FAST_RAM uint32_t totalWaitingTasks;
static FAST_RAM uint32_t totalWaitingTasksSamples;
static bool calculateTaskStatistics;
uint16_t averageSystemLoadPercent = 0;
static FAST_RAM bool calculateTaskStatistics;
FAST_RAM uint16_t averageSystemLoadPercent = 0;
static int taskQueuePos = 0;
STATIC_UNIT_TESTED int taskQueueSize = 0;
static FAST_RAM int taskQueuePos = 0;
STATIC_UNIT_TESTED FAST_RAM int taskQueueSize = 0;
// No need for a linked list for the queue, since items are only inserted at startup
STATIC_UNIT_TESTED cfTask_t* taskQueueArray[TASK_COUNT + 1]; // extra item for NULL pointer at end of queue
STATIC_UNIT_TESTED FAST_RAM cfTask_t* taskQueueArray[TASK_COUNT + 1]; // extra item for NULL pointer at end of queue
void queueClear(void)
{

View file

@ -67,7 +67,7 @@
#endif
acc_t acc; // acc access functions
FAST_RAM acc_t acc; // acc access functions
static float accumulatedMeasurements[XYZ_AXIS_COUNT];
static int accumulatedMeasurementCount;

View file

@ -74,12 +74,12 @@
#define USE_GYRO_SLEW_LIMITER
#endif
gyro_t gyro;
static uint8_t gyroDebugMode;
FAST_RAM gyro_t gyro;
static FAST_RAM uint8_t gyroDebugMode;
static float accumulatedMeasurements[XYZ_AXIS_COUNT];
static timeUs_t accumulatedMeasurementTimeUs;
static timeUs_t accumulationLastTimeSampledUs;
static FAST_RAM float accumulatedMeasurements[XYZ_AXIS_COUNT];
static FAST_RAM timeUs_t accumulatedMeasurementTimeUs;
static FAST_RAM timeUs_t accumulationLastTimeSampledUs;
typedef struct gyroCalibration_s {
int32_t sum[XYZ_AXIS_COUNT];
@ -111,7 +111,7 @@ typedef struct gyroSensor_s {
biquadFilter_t notchFilterDyn[XYZ_AXIS_COUNT];
} gyroSensor_t;
static gyroSensor_t gyroSensor1;
static FAST_RAM gyroSensor_t gyroSensor1;
static void gyroInitSensorFilters(gyroSensor_t *gyroSensor);

View file

@ -82,6 +82,17 @@
#define FAST_CODE
#endif
#ifdef USE_FAST_RAM
#ifdef __APPLE__
#define FAST_RAM __attribute__ ((section("__DATA,__.fastram_bss"), aligned(4)))
#else
#define FAST_RAM __attribute__ ((section(".fastram_bss"), aligned(4)))
#endif
#else
#define FAST_RAM
#endif // USE_FAST_RAM
#define USE_CLI
#define USE_PPM
#define USE_PWM

View file

@ -57,6 +57,7 @@
#endif
#define FAST_CODE
#define FAST_RAM
//CLI needs FC dependencies removed before we can compile it, disabling for now
//#define USE_CLI

View file

@ -125,6 +125,15 @@ SECTIONS
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM
.fastram_bss (NOLOAD) :
{
__fastram_bss_start__ = .;
*(.fastram_bss)
*(SORT_BY_ALIGNMENT(.fastram_bss*))
. = ALIGN(4);
__fastram_bss_end__ = .;
} >FASTRAM
/* User_heap_stack section, used to check that there is enough RAM left */
_heap_stack_end = ORIGIN(STACKRAM)+LENGTH(STACKRAM) - 8; /* 8 bytes to allow for alignment */

View file

@ -20,5 +20,6 @@ MEMORY
}
REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("FASTRAM", RAM)
INCLUDE "stm32_flash.ld"

View file

@ -21,5 +21,6 @@ MEMORY
}
REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("FASTRAM", RAM)
INCLUDE "stm32_flash.ld"

View file

@ -20,5 +20,6 @@ MEMORY
}
REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("FASTRAM", RAM)
INCLUDE "stm32_flash.ld"

View file

@ -20,5 +20,6 @@ MEMORY
}
REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("FASTRAM", RAM)
INCLUDE "stm32_flash.ld"

View file

@ -21,5 +21,6 @@ MEMORY
}
REGION_ALIAS("STACKRAM", CCM)
REGION_ALIAS("FASTRAM", CCM)
INCLUDE "stm32_flash.ld"

View file

@ -21,5 +21,6 @@ MEMORY
}
REGION_ALIAS("STACKRAM", CCM)
REGION_ALIAS("FASTRAM", CCM)
INCLUDE "stm32_flash.ld"

View file

@ -33,5 +33,6 @@ MEMORY
}
REGION_ALIAS("STACKRAM", CCM)
REGION_ALIAS("FASTRAM", CCM)
INCLUDE "stm32_flash_split.ld"
INCLUDE "stm32_flash_split.ld"

View file

@ -33,5 +33,6 @@ MEMORY
}
REGION_ALIAS("STACKRAM", CCM)
REGION_ALIAS("FASTRAM", CCM)
INCLUDE "stm32_flash_split.ld"

View file

@ -27,9 +27,11 @@ MEMORY
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
CCM (xrw) : ORIGIN = 0x10000000, LENGTH = 64K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("STACKRAM", CCM)
REGION_ALIAS("FASTRAM", CCM)
INCLUDE "stm32_flash_split.ld"

View file

@ -33,5 +33,6 @@ MEMORY
}
REGION_ALIAS("STACKRAM", CCM)
REGION_ALIAS("FASTRAM", CCM)
INCLUDE "stm32_flash_split.ld"

View file

@ -31,5 +31,6 @@ MEMORY
}
REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("FASTRAM", RAM)
INCLUDE "stm32_flash_split.ld"

View file

@ -39,5 +39,6 @@ MEMORY
/* note TCM could be used for stack */
REGION_ALIAS("STACKRAM", TCM)
REGION_ALIAS("FASTRAM", TCM)
INCLUDE "stm32_flash_split.ld"

View file

@ -32,5 +32,6 @@ MEMORY
}
/* note CCM could be used for stack */
REGION_ALIAS("STACKRAM", TCM)
REGION_ALIAS("FASTRAM", TCM)
INCLUDE "stm32_flash_split.ld"

View file

@ -32,5 +32,6 @@ MEMORY
}
/* note CCM could be used for stack */
REGION_ALIAS("STACKRAM", TCM)
REGION_ALIAS("FASTRAM", TCM)
INCLUDE "stm32_flash_split.ld"

View file

@ -126,6 +126,15 @@ SECTIONS
__bss_end__ = _ebss;
} >RAM
.fastram_bss (NOLOAD) :
{
__fastram_bss_start__ = .;
*(.fastram_bss)
*(SORT_BY_ALIGNMENT(.fastram_bss*))
. = ALIGN(4);
__fastram_bss_end__ = .;
} >FASTRAM
/* User_heap_stack section, used to check that there is enough RAM left */
_heap_stack_end = ORIGIN(STACKRAM)+LENGTH(STACKRAM) - 8; /* 8 bytes to allow for alignment */
_heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size;

View file

@ -26,6 +26,7 @@
#define U_ID_2 2
#define FAST_CODE
#define FAST_RAM
#define MAX_PROFILE_COUNT 3
#define USE_MAG