GCS_MAVLink: moved send_meminfo() to GCS_Common.cpp
This commit is contained in:
parent
72473e4317
commit
af124a8a45
@ -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);
|
||||
|
||||
|
@ -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());
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user