Rover: fixed type of payload size

This commit is contained in:
Andrew Tridgell 2012-09-25 07:20:54 +10:00
parent 9f9d570597
commit e04de04cbd

View File

@ -516,7 +516,7 @@ static bool telemetry_delayed(mavlink_channel_t chan)
// try to send a message, return false if it won't fit in the serial tx buffer
static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, uint16_t packet_drops)
{
int payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
if (telemetry_delayed(chan)) {
return false;