From 3b2ef31cc0aca9cb415b504da9754a3557000f32 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 28 Dec 2013 16:02:45 +1100 Subject: [PATCH] Rover: use common available_memory() --- APMrover2/APMrover2.pde | 2 -- APMrover2/GCS_Mavlink.pde | 10 +--------- APMrover2/Log.pde | 2 +- APMrover2/system.pde | 2 +- 4 files changed, 3 insertions(+), 13 deletions(-) diff --git a/APMrover2/APMrover2.pde b/APMrover2/APMrover2.pde index af64f78905..80934a7062 100644 --- a/APMrover2/APMrover2.pde +++ b/APMrover2/APMrover2.pde @@ -84,7 +84,6 @@ #include // MAVLink GCS definitions #include // needed for AHRS build #include // needed for AHRS build -#include #include #include // RC input mapping library #include @@ -582,7 +581,6 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = { setup is called when the sketch starts */ void setup() { - memcheck_init(); cliSerial = hal.console; // load the default values of variables listed in var_info[] diff --git a/APMrover2/GCS_Mavlink.pde b/APMrover2/GCS_Mavlink.pde index 29a403a693..6bdebf4637 100644 --- a/APMrover2/GCS_Mavlink.pde +++ b/APMrover2/GCS_Mavlink.pde @@ -188,14 +188,6 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack } -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()); -#endif -} - static void NOINLINE send_location(mavlink_channel_t chan) { uint32_t fix_time; @@ -529,7 +521,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, case MSG_EXTENDED_STATUS2: CHECK_PAYLOAD_SIZE(MEMINFO); - send_meminfo(chan); + gcs[chan-MAVLINK_COMM_0].send_meminfo(); break; case MSG_ATTITUDE: diff --git a/APMrover2/Log.pde b/APMrover2/Log.pde index 939f92bd51..8848c8559f 100644 --- a/APMrover2/Log.pde +++ b/APMrover2/Log.pde @@ -550,7 +550,7 @@ static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_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/APMrover2/system.pde b/APMrover2/system.pde index 67967afbbd..4498e6d7db 100644 --- a/APMrover2/system.pde +++ b/APMrover2/system.pde @@ -96,7 +96,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()); // // Check the EEPROM format version before loading any parameters from EEPROM.