@ -66,6 +66,13 @@ RemoteIDManager::RemoteIDManager(Vehicle* vehicle)
@@ -66,6 +66,13 @@ RemoteIDManager::RemoteIDManager(Vehicle* vehicle)
// Assign vehicle sysid and compid. GCS must target these messages to autopilot, and autopilot will redirect them to RID device
_targetSystem = _vehicle - > id ( ) ;
_targetComponent = _vehicle - > compId ( ) ;
if ( _settings - > operatorIDValid ( ) - > rawValue ( ) = = true ) {
// If it was already checked, we can flag this as good to go.
// We don't do a fresh verification because we don't store the private part of the ID.
_operatorIDGood = true ;
operatorIDGoodChanged ( ) ;
}
}
void RemoteIDManager : : mavlinkMessageReceived ( mavlink_message_t & message )
@ -114,7 +121,6 @@ void RemoteIDManager::_handleArmStatus(mavlink_message_t& message)
@@ -114,7 +121,6 @@ void RemoteIDManager::_handleArmStatus(mavlink_message_t& message)
_commsGood = true ;
_sendMessagesTimer . start ( ) ; // Start sending our messages
_checkGCSBasicID ( ) ; // Check if basicID is good to send
checkOperatorID ( ) ; // Check if OperatorID is good in case we want to send it from start because of the settings
emit commsGoodChanged ( ) ;
qCDebug ( RemoteIDManagerLog ) < < " Receiving ODID_ARM_STATUS from RID device " ;
}
@ -398,18 +404,85 @@ void RemoteIDManager::_checkGCSBasicID()
@@ -398,18 +404,85 @@ void RemoteIDManager::_checkGCSBasicID()
}
}
void RemoteIDManager : : checkOperatorID ( )
void RemoteIDManager : : checkOperatorID ( const QString & operatorID )
{
// We overwrite the fact that is also set by the text input but we want to update
// after every letter rather than when editing is done.
// We check whether it actually changed to avoid triggering this on startup.
if ( operatorID ! = _settings - > operatorID ( ) - > rawValueString ( ) ) {
_settings - > operatorIDValid ( ) - > setRawValue ( _isEUOperatorIDValid ( operatorID ) ) ;
}
}
void RemoteIDManager : : setOperatorID ( )
{
QString operatorID = _settings - > operatorID ( ) - > rawValue ( ) . toString ( ) ;
if ( ! operatorID . isEmpty ( ) & & ( _settings - > operatorIDType ( ) - > rawValue ( ) . toInt ( ) > = 0 ) ) {
_operatorIDGood = true ;
if ( _settings - > region ( ) - > rawValue ( ) . toInt ( ) = = Region : : EU ) {
// Save for next time because we don't save the private part,
// so we can't re-verify next time and just trust the value
// in the settings.
_operatorIDGood = _settings - > operatorIDValid ( ) - > rawValue ( ) = = true ;
if ( _operatorIDGood ) {
// Strip private part
_settings - > operatorID ( ) - > setRawValue ( operatorID . sliced ( 0 , 16 ) ) ;
}
} else {
_operatorIDGood = false ;
// Otherwise, we just check if there is anything entered
_operatorIDGood =
( ! operatorID . isEmpty ( ) & & ( _settings - > operatorIDType ( ) - > rawValue ( ) . toInt ( ) > = 0 ) ) ;
}
emit operatorIDGoodChanged ( ) ;
}
bool RemoteIDManager : : _isEUOperatorIDValid ( const QString & operatorID ) const
{
const bool containsDash = operatorID . contains ( ' - ' ) ;
if ( ! ( operatorID . length ( ) = = 20 & & containsDash ) & & ! ( operatorID . length ( ) = = 19 & & ! containsDash ) ) {
qCDebug ( RemoteIDManagerLog ) < < " OperatorID not long enough " ;
return false ;
}
const QString countryCode = operatorID . sliced ( 0 , 3 ) ;
if ( ! countryCode . isUpper ( ) ) {
qCDebug ( RemoteIDManagerLog ) < < " OperatorID country code not uppercase " ;
return false ;
}
const QString number = operatorID . sliced ( 3 , 12 ) ;
const QChar checksum = operatorID . at ( 15 ) ;
const QString secret = containsDash ? operatorID . sliced ( 17 , 3 ) : operatorID . sliced ( 16 , 3 ) ;
const QString combination = number + secret ;
const QChar result = _calculateLuhnMod36 ( combination ) ;
const bool valid = ( result = = checksum ) ;
qCDebug ( RemoteIDManagerLog ) < < " Operator ID checksum " < < ( valid ? " valid " : " invalid " ) ;
return valid ;
}
QChar RemoteIDManager : : _calculateLuhnMod36 ( const QString & input ) const {
const int n = 36 ;
const QString alphabet = " 0123456789abcdefghijklmnopqrstuvwxyz " ;
int sum = 0 ;
int factor = 2 ;
for ( int i = input . length ( ) - 1 ; i > = 0 ; i - - ) {
int codePoint = alphabet . indexOf ( input [ i ] ) ;
int addend = factor * codePoint ;
factor = ( factor = = 2 ) ? 1 : 2 ;
addend = ( addend / n ) + ( addend % n ) ;
sum + = addend ;
}
int remainder = sum % n ;
int checkCodePoint = ( n - remainder ) % n ;
return alphabet . at ( checkCodePoint ) ;
}
void RemoteIDManager : : setEmergency ( bool declare )
{
_emergencyDeclared = declare ;