From af124a8a45a30916cd6b82464619523913fe7ce7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 28 Dec 2013 16:00:19 +1100 Subject: [PATCH] GCS_MAVLink: moved send_meminfo() to GCS_Common.cpp --- libraries/GCS_MAVLink/GCS.h | 3 +++ libraries/GCS_MAVLink/GCS_Common.cpp | 11 +++++++++++ 2 files changed, 14 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 5fbb766f05..5a35a03725 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -178,6 +178,9 @@ public: uint32_t last_heartbeat_time; // milliseconds + // common send functions + void send_meminfo(void); + private: void handleMessage(mavlink_message_t * msg); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index e0c070166c..37d49adf6f 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -138,3 +138,14 @@ GCS_MAVLINK::queued_waypoint_send() void GCS_MAVLINK::reset_cli_timeout() { _cli_timeout = hal.scheduler->millis(); } + +void GCS_MAVLINK::send_meminfo(void) +{ +#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2 + extern unsigned __brkval; +#else + unsigned __brkval = 0; +#endif + mavlink_msg_meminfo_send(chan, __brkval, hal.util->available_memory()); +} +