AntennaTracker: avoid integer underflow in mavlink txspace check
This commit is contained in:
parent
b82457eaa6
commit
1aeac23f46
@ -7,7 +7,7 @@
|
||||
static bool in_mavlink_delay;
|
||||
|
||||
// check if a message will fit in the payload space available
|
||||
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_ ## id ## _LEN) return false
|
||||
#define CHECK_PAYLOAD_SIZE(id) if (txspace < MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_ ## id ## _LEN) return false
|
||||
|
||||
/*
|
||||
* !!NOTE!!
|
||||
@ -166,7 +166,7 @@ static void NOINLINE send_simstate(mavlink_channel_t chan)
|
||||
// try to send a message, return false if it won't fit in the serial tx buffer
|
||||
bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
||||
{
|
||||
int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
uint16_t txspace = comm_get_txspace(chan);
|
||||
switch (id) {
|
||||
case MSG_HEARTBEAT:
|
||||
CHECK_PAYLOAD_SIZE(HEARTBEAT);
|
||||
|
Loading…
Reference in New Issue
Block a user