mirror of https://github.com/ArduPilot/ardupilot
use memcheck_available_memory() instead of freeRAM()
this provides a more accurate view of memory
This commit is contained in:
parent
6899189395
commit
85e8316809
|
@ -75,7 +75,7 @@ static void init_ardupilot()
|
|||
|
||||
Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE
|
||||
"\n\nFree RAM: %lu\n"),
|
||||
freeRAM());
|
||||
memcheck_available_memory());
|
||||
|
||||
|
||||
//
|
||||
|
@ -503,21 +503,6 @@ init_optflow()
|
|||
}
|
||||
#endif
|
||||
|
||||
/* 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;
|
||||
}
|
||||
|
||||
static void
|
||||
init_simple_bearing()
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue