mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Plane: use AP_HAL available_memory() call
This commit is contained in:
parent
75cb04dd8b
commit
72473e4317
@ -51,7 +51,6 @@
|
|||||||
#include <AP_Relay.h> // APM relay
|
#include <AP_Relay.h> // APM relay
|
||||||
#include <AP_Camera.h> // Photo or video camera
|
#include <AP_Camera.h> // Photo or video camera
|
||||||
#include <AP_Airspeed.h>
|
#include <AP_Airspeed.h>
|
||||||
#include <memcheck.h>
|
|
||||||
|
|
||||||
#include <APM_OBC.h>
|
#include <APM_OBC.h>
|
||||||
#include <APM_Control.h>
|
#include <APM_Control.h>
|
||||||
@ -763,10 +762,6 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
|||||||
AP_Param param_loader(var_info, WP_START_BYTE);
|
AP_Param param_loader(var_info, WP_START_BYTE);
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
// this needs to be the first call, as it fills memory with
|
|
||||||
// sentinel values
|
|
||||||
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[]
|
||||||
|
@ -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
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
extern unsigned __brkval;
|
extern unsigned __brkval;
|
||||||
mavlink_msg_meminfo_send(chan, __brkval, memcheck_available_memory());
|
mavlink_msg_meminfo_send(chan, __brkval, hal.util->available_memory());
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -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
|
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));
|
||||||
|
|
||||||
|
@ -78,7 +78,7 @@ static void geofence_load(void)
|
|||||||
uint8_t i;
|
uint8_t i;
|
||||||
|
|
||||||
if (geofence_state == NULL) {
|
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
|
// too risky to enable as we could run out of stack
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
@ -84,7 +84,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());
|
||||||
|
|
||||||
|
|
||||||
//
|
//
|
||||||
|
Loading…
Reference in New Issue
Block a user