Browse Source

Rover: use common available_memory()

master
Andrew Tridgell 11 years ago
parent
commit
3b2ef31cc0
  1. 2
      APMrover2/APMrover2.pde
  2. 10
      APMrover2/GCS_Mavlink.pde
  3. 2
      APMrover2/Log.pde
  4. 2
      APMrover2/system.pde

2
APMrover2/APMrover2.pde

@ -84,7 +84,6 @@ @@ -84,7 +84,6 @@
#include <GCS_MAVLink.h> // MAVLink GCS definitions
#include <AP_Airspeed.h> // needed for AHRS build
#include <AP_Vehicle.h> // needed for AHRS build
#include <memcheck.h>
#include <DataFlash.h>
#include <AP_RCMapper.h> // RC input mapping library
#include <SITL.h>
@ -582,7 +581,6 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = { @@ -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[]

10
APMrover2/GCS_Mavlink.pde

@ -188,14 +188,6 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack @@ -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, @@ -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:

2
APMrover2/Log.pde

@ -550,7 +550,7 @@ static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page) @@ -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));

2
APMrover2/system.pde

@ -96,7 +96,7 @@ static void init_ardupilot() @@ -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.

Loading…
Cancel
Save