mirror of https://github.com/ArduPilot/ardupilot
Plane: use common send_meminfo()
This commit is contained in:
parent
a95868e124
commit
3486b933c0
|
@ -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:
|
||||
|
|
Loading…
Reference in New Issue