Plane: use AP_HAL available_memory() call

This commit is contained in:
Andrew Tridgell 2013-12-28 14:51:37 +11:00
parent 75cb04dd8b
commit 72473e4317
5 changed files with 4 additions and 9 deletions

View File

@ -51,7 +51,6 @@
#include <AP_Relay.h> // APM relay
#include <AP_Camera.h> // Photo or video camera
#include <AP_Airspeed.h>
#include <memcheck.h>
#include <APM_OBC.h>
#include <APM_Control.h>
@ -763,10 +762,6 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
AP_Param param_loader(var_info, WP_START_BYTE);
void setup() {
// this needs to be the first call, as it fills memory with
// sentinel values
memcheck_init();
cliSerial = hal.console;
// load the default values of variables listed in var_info[]

View File

@ -246,7 +246,7 @@ static void NOINLINE send_meminfo(mavlink_channel_t chan)
{
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
extern unsigned __brkval;
mavlink_msg_meminfo_send(chan, __brkval, memcheck_available_memory());
mavlink_msg_meminfo_send(chan, __brkval, hal.util->available_memory());
#endif
}

View File

@ -555,7 +555,7 @@ static void Log_Read(uint16_t log_num, int16_t start_page, int16_t end_page)
{
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
"\nFree RAM: %u\n"),
(unsigned) memcheck_available_memory());
(unsigned)hal.util->available_memory());
cliSerial->println_P(PSTR(HAL_BOARD_NAME));

View File

@ -78,7 +78,7 @@ static void geofence_load(void)
uint8_t i;
if (geofence_state == NULL) {
if (memcheck_available_memory() < 512 + sizeof(struct GeofenceState)) {
if (hal.util->available_memory() < 512 + sizeof(struct GeofenceState)) {
// too risky to enable as we could run out of stack
goto failed;
}

View File

@ -84,7 +84,7 @@ static void init_ardupilot()
cliSerial->printf_P(PSTR("\n\nInit " FIRMWARE_STRING
"\n\nFree RAM: %u\n"),
memcheck_available_memory());
hal.util->available_memory());
//