@ -145,12 +145,12 @@ void MAVLinkProtocol::storeSettings()
@@ -145,12 +145,12 @@ void MAVLinkProtocol::storeSettings()
void MAVLinkProtocol : : resetMetadataForLink ( const LinkInterface * link )
{
int linkId = link - > getId ( ) ;
totalReceiveCounter [ linkId ] = 0 ;
totalLossCounter [ linkId ] = 0 ;
totalErrorCounter [ linkId ] = 0 ;
currReceiveCounter [ linkId ] = 0 ;
currLossCounter [ linkId ] = 0 ;
int channe l = link - > getMavlinkChannel ( ) ;
totalReceiveCounter [ channe l] = 0 ;
totalLossCounter [ channe l] = 0 ;
totalErrorCounter [ channe l] = 0 ;
currReceiveCounter [ channe l] = 0 ;
currLossCounter [ channe l] = 0 ;
}
void MAVLinkProtocol : : linkConnected ( void )
@ -227,8 +227,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
@@ -227,8 +227,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
mavlink_message_t message ;
mavlink_status_t status ;
// Cache the link ID for common use.
int linkId = link - > getId ( ) ;
int mavlinkChannel = link - > getMavlinkChannel ( ) ;
static int mavlink09Count = 0 ;
static int nonmavlinkCount = 0 ;
@ -237,9 +236,8 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
@@ -237,9 +236,8 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
static bool checkedUserNonMavlink = false ;
static bool warnedUserNonMavlink = false ;
// FIXME: Add check for if link->getId() >= MAVLINK_COMM_NUM_BUFFERS
for ( int position = 0 ; position < b . size ( ) ; position + + ) {
unsigned int decodeState = mavlink_parse_char ( linkId , ( uint8_t ) ( b [ position ] ) , & message , & status ) ;
unsigned int decodeState = mavlink_parse_char ( mavlinkChannel , ( uint8_t ) ( b [ position ] ) , & message , & status ) ;
if ( ( uint8_t ) b [ position ] = = 0x55 ) mavlink09Count + + ;
if ( ( mavlink09Count > 100 ) & & ! decodedFirstPacket & & ! warnedUser )
@ -381,8 +379,8 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
@@ -381,8 +379,8 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
}
// Increase receive counter
totalReceiveCounter [ linkId ] + + ;
currReceiveCounter [ linkId ] + + ;
totalReceiveCounter [ mavlinkChannel ] + + ;
currReceiveCounter [ mavlinkChannel ] + + ;
// Determine what the next expected sequence number is, accounting for
// never having seen a message for this system/component pair.
@ -403,22 +401,22 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
@@ -403,22 +401,22 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
}
// And log how many were lost for all time and just this timestep
totalLossCounter [ linkId ] + = lostMessages ;
currLossCounter [ linkId ] + = lostMessages ;
totalLossCounter [ mavlinkChannel ] + = lostMessages ;
currLossCounter [ mavlinkChannel ] + = lostMessages ;
}
// And update the last sequence number for this system/component pair
lastIndex [ message . sysid ] [ message . compid ] = expectedSeq ;
// Update on every 32th packet
if ( ( totalReceiveCounter [ linkId ] & 0x1F ) = = 0 )
if ( ( totalReceiveCounter [ mavlinkChannel ] & 0x1F ) = = 0 )
{
// Calculate new loss ratio
// Receive loss
float receiveLoss = ( double ) currLossCounter [ linkId ] / ( double ) ( currReceiveCounter [ linkId ] + currLossCounter [ linkId ] ) ;
float receiveLoss = ( double ) currLossCounter [ mavlinkChannel ] / ( double ) ( currReceiveCounter [ mavlinkChannel ] + currLossCounter [ mavlinkChannel ] ) ;
receiveLoss * = 100.0f ;
currLossCounter [ linkId ] = 0 ;
currReceiveCounter [ linkId ] = 0 ;
currLossCounter [ mavlinkChannel ] = 0 ;
currReceiveCounter [ mavlinkChannel ] = 0 ;
emit receiveLossChanged ( message . sysid , receiveLoss ) ;
}
@ -497,7 +495,7 @@ void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message
@@ -497,7 +495,7 @@ void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message
static uint8_t buffer [ MAVLINK_MAX_PACKET_LEN ] ;
// Rewriting header to ensure correct link ID is set
static uint8_t messageKeys [ 256 ] = MAVLINK_MESSAGE_CRCS ;
if ( link - > getId ( ) ! = 0 ) mavlink_finalize_message_chan ( & message , this - > getSystemId ( ) , this - > getComponentId ( ) , link - > getId ( ) , message . len , messageKeys [ message . msgid ] ) ;
mavlink_finalize_message_chan ( & message , this - > getSystemId ( ) , this - > getComponentId ( ) , link - > getMavlinkChannel ( ) , message . len , messageKeys [ message . msgid ] ) ;
// Write message into buffer, prepending start sign
int len = mavlink_msg_to_send_buffer ( buffer , & message ) ;
// If link is connected
@ -520,7 +518,7 @@ void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message
@@ -520,7 +518,7 @@ void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message
static uint8_t buffer [ MAVLINK_MAX_PACKET_LEN ] ;
// Rewriting header to ensure correct link ID is set
static uint8_t messageKeys [ 256 ] = MAVLINK_MESSAGE_CRCS ;
if ( link - > getId ( ) ! = 0 ) mavlink_finalize_message_chan ( & message , systemid , componentid , link - > getId ( ) , message . len , messageKeys [ message . msgid ] ) ;
mavlink_finalize_message_chan ( & message , systemid , componentid , link - > getMavlinkChannel ( ) , message . len , messageKeys [ message . msgid ] ) ;
// Write message into buffer, prepending start sign
int len = mavlink_msg_to_send_buffer ( buffer , & message ) ;
// If link is connected