Rover: use common available_memory()

This commit is contained in:
Andrew Tridgell 2013-12-28 16:02:45 +11:00
parent 97df2f64c9
commit 3b2ef31cc0
4 changed files with 3 additions and 13 deletions

View File

@ -84,7 +84,6 @@
#include <GCS_MAVLink.h> // MAVLink GCS definitions #include <GCS_MAVLink.h> // MAVLink GCS definitions
#include <AP_Airspeed.h> // needed for AHRS build #include <AP_Airspeed.h> // needed for AHRS build
#include <AP_Vehicle.h> // needed for AHRS build #include <AP_Vehicle.h> // needed for AHRS build
#include <memcheck.h>
#include <DataFlash.h> #include <DataFlash.h>
#include <AP_RCMapper.h> // RC input mapping library #include <AP_RCMapper.h> // RC input mapping library
#include <SITL.h> #include <SITL.h>
@ -582,7 +581,6 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
setup is called when the sketch starts setup is called when the sketch starts
*/ */
void setup() { void setup() {
memcheck_init();
cliSerial = hal.console; cliSerial = hal.console;
// load the default values of variables listed in var_info[] // load the default values of variables listed in var_info[]

View File

@ -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) static void NOINLINE send_location(mavlink_channel_t chan)
{ {
uint32_t fix_time; 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: case MSG_EXTENDED_STATUS2:
CHECK_PAYLOAD_SIZE(MEMINFO); CHECK_PAYLOAD_SIZE(MEMINFO);
send_meminfo(chan); gcs[chan-MAVLINK_COMM_0].send_meminfo();
break; break;
case MSG_ATTITUDE: case MSG_ATTITUDE:

View File

@ -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 cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
"\nFree RAM: %u\n"), "\nFree RAM: %u\n"),
(unsigned) memcheck_available_memory()); (unsigned)hal.util->available_memory());
cliSerial->println_P(PSTR(HAL_BOARD_NAME)); cliSerial->println_P(PSTR(HAL_BOARD_NAME));

View File

@ -96,7 +96,7 @@ static void init_ardupilot()
cliSerial->printf_P(PSTR("\n\nInit " FIRMWARE_STRING cliSerial->printf_P(PSTR("\n\nInit " FIRMWARE_STRING
"\n\nFree RAM: %u\n"), "\n\nFree RAM: %u\n"),
memcheck_available_memory()); hal.util->available_memory());
// //
// Check the EEPROM format version before loading any parameters from EEPROM. // Check the EEPROM format version before loading any parameters from EEPROM.