diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 4ea549dbfa..3a9a158946 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -51,7 +51,6 @@ #include // APM relay #include // Photo or video camera #include -#include #include #include @@ -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[] diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index e41c437fef..b4a28ffd9b 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -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 } diff --git a/ArduPlane/Log.pde b/ArduPlane/Log.pde index 9635cbef65..def5eb79a3 100644 --- a/ArduPlane/Log.pde +++ b/ArduPlane/Log.pde @@ -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)); diff --git a/ArduPlane/geofence.pde b/ArduPlane/geofence.pde index 5cd4b247c5..fcceb54b55 100644 --- a/ArduPlane/geofence.pde +++ b/ArduPlane/geofence.pde @@ -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; } diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index 0a6c1ec7b5..8d597b46c7 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -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()); //