mirror of https://github.com/ArduPilot/ardupilot
Found free extra 256 bytes of RAM eliminate _clz use from libgcc
Believe it or not, changing / 2^31 to >>31 saved 256 bytes in the "d" segment. The reason is that GCC version prior to 4.3.5 does not have a count_leading_zeros (clz) assembler macro, so it uses a 256 byte lookup table called _clz The _clz table gets pulled in if you do 64 bit division. This tiny change is the only place that we do long long division. Changing to a shift saves 256 bytes of ram.
This commit is contained in:
parent
d0c67debee
commit
5255512bf9
|
@ -212,10 +212,10 @@ void AP_Baro_MS5611::_calculate()
|
|||
SENS = (int64_t)C1 * 32768 + ((int64_t)C3 * dT) / 256;
|
||||
|
||||
if (TEMP < 2000){ // second order temperature compensation
|
||||
int64_t T2 = (((int64_t)dT)*dT) / 2147483648UL;
|
||||
int64_t T2 = (((int64_t)dT)*dT) >> 31;
|
||||
int64_t Aux_64 = (TEMP-2000)*(TEMP-2000);
|
||||
int64_t OFF2 = 5*Aux_64/2;
|
||||
int64_t SENS2 = 5*Aux_64/4;
|
||||
int64_t OFF2 = (5*Aux_64)>>1;
|
||||
int64_t SENS2 = (5*Aux_64)>>2;
|
||||
TEMP = TEMP - T2;
|
||||
OFF = OFF - OFF2;
|
||||
SENS = SENS - SENS2;
|
||||
|
|
Loading…
Reference in New Issue