Browse Source

use memcheck_available_memory() instead of freeRAM()

this gives a more accurate view of free memory
mission-4.1.18
Andrew Tridgell 14 years ago
parent
commit
63ac6bcd94
  1. 2
      ArduPlane/Log.pde
  2. 19
      ArduPlane/system.pde

2
ArduPlane/Log.pde

@ -651,7 +651,7 @@ static void Log_Read(int start_page, int end_page) @@ -651,7 +651,7 @@ static void Log_Read(int start_page, int end_page)
#endif
Serial.printf_P(PSTR("\n" THISFIRMWARE
"\nFree RAM: %lu\n"),
freeRAM());
memcheck_available_memory());
DataFlash.StartRead(start_page);
while (page < end_page && page != -1){

19
ArduPlane/system.pde

@ -72,7 +72,7 @@ static void init_ardupilot() @@ -72,7 +72,7 @@ static void init_ardupilot()
Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE
"\n\nFree RAM: %lu\n"),
freeRAM());
memcheck_available_memory());
//
// Check the EEPROM format version before loading any parameters from EEPROM.
@ -482,23 +482,6 @@ static void resetPerfData(void) { @@ -482,23 +482,6 @@ static void resetPerfData(void) {
}
/*
* This function gets the current value of the heap and stack pointers.
* The stack pointer starts at the top of RAM and grows downwards. The heap pointer
* starts just above the static variables etc. and grows upwards. SP should always
* be larger than HP or you'll be in big trouble! The smaller the gap, the more
* careful you need to be. Julian Gall 6 - Feb - 2009.
*/
static unsigned long freeRAM() {
uint8_t * heapptr, * stackptr;
stackptr = (uint8_t *)malloc(4); // use stackptr temporarily
heapptr = stackptr; // save value of heap pointer
free(stackptr); // free up the memory again (sets stackptr to 0)
stackptr = (uint8_t *)(SP); // save value of stack pointer
return stackptr - heapptr;
}
/*
map from a 8 bit EEPROM baud rate to a real baud rate
*/

Loading…
Cancel
Save