GCS_MAVLink: added comm_is_idle() function

this will make CLI detection more reliable
This commit is contained in:
Andrew Tridgell 2013-03-21 21:55:12 +11:00
parent 0e37ae4400
commit 7e58bde826
2 changed files with 18 additions and 0 deletions

View File

@ -75,3 +75,15 @@ uint8_t mavlink_get_message_crc(uint8_t msgid)
{
return pgm_read_byte(&mavlink_message_crc_progmem[msgid]);
}
extern const AP_HAL::HAL& hal;
/*
return true if the MAVLink parser is idle, so there is no partly parsed
MAVLink message being processed
*/
bool comm_is_idle(mavlink_channel_t chan)
{
mavlink_status_t *status = mavlink_get_channel_status(chan);
return status == NULL || status->parse_state <= MAVLINK_PARSE_STATE_IDLE;
}

View File

@ -142,6 +142,12 @@ static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
}
#endif
/*
return true if the MAVLink parser is idle, so there is no partly parsed
MAVLink message being processed
*/
bool comm_is_idle(mavlink_channel_t chan);
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
#include "include/mavlink/v1.0/ardupilotmega/mavlink.h"