mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Copter: use common available_memory()
This commit is contained in:
parent
3486b933c0
commit
97df2f64c9
@ -123,7 +123,6 @@
|
||||
#include <AC_WPNav.h> // ArduCopter waypoint navigation library
|
||||
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
#include <AC_Fence.h> // Arducopter Fence library
|
||||
#include <memcheck.h> // memory limit checker
|
||||
#include <SITL.h> // software in the loop support
|
||||
#include <AP_Scheduler.h> // main loop scheduler
|
||||
#include <AP_RCMapper.h> // RC input mapping library
|
||||
@ -904,11 +903,8 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
||||
};
|
||||
|
||||
|
||||
void setup() {
|
||||
|
||||
// this needs to be the first call, as it fills memory with
|
||||
// sentinel values
|
||||
memcheck_init();
|
||||
void setup()
|
||||
{
|
||||
cliSerial = hal.console;
|
||||
|
||||
// Load the default values of variables listed in var_info[]s
|
||||
|
@ -218,14 +218,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;
|
||||
@ -584,7 +576,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:
|
||||
|
@ -787,7 +787,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));
|
||||
|
||||
|
@ -105,7 +105,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());
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user