From 3486b933c01507285cdcff4eb2b66f6ecb8e0b56 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 28 Dec 2013 16:02:06 +1100 Subject: [PATCH] Plane: use common send_meminfo() --- ArduPlane/GCS_Mavlink.pde | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index b4a28ffd9b..94abbbfd78 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -242,14 +242,6 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) } -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, hal.util->available_memory()); -#endif -} - static void NOINLINE send_location(mavlink_channel_t chan) { uint32_t fix_time; @@ -631,7 +623,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: