@ -34,9 +34,10 @@ QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")
@@ -34,9 +34,10 @@ QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")
MissionManager : : MissionManager ( Vehicle * vehicle )
: _vehicle ( vehicle )
, _cMissionItems ( 0 )
, _ackTimeoutTimer ( NULL )
, _retryAck ( AckNone )
, _readTransactionInProgress ( false )
, _writeTransactionInProgress ( false )
{
connect ( _vehicle , & Vehicle : : mavlinkMessageReceived , this , & MissionManager : : _mavlinkMessageReceived ) ;
@ -56,7 +57,6 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
@@ -56,7 +57,6 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
{
bool skipFirstItem = ! _vehicle - > firmwarePlugin ( ) - > sendHomePositionToVehicle ( ) ;
_retryCount = 0 ;
_missionItems . clear ( ) ;
int firstIndex = skipFirstItem ? 1 : 0 ;
@ -83,31 +83,15 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
@@ -83,31 +83,15 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
return ;
}
mavlink_message_t message ;
mavlink_mission_count_t missionCount ;
_expectedSequenceNumber = 0 ;
missionCount . target_system = _vehicle - > id ( ) ;
missionCount . target_component = MAV_COMP_ID_MISSIONPLANNER ;
missionCount . count = _missionItems . count ( ) ;
mavlink_msg_mission_count_encode ( qgcApp ( ) - > toolbox ( ) - > mavlinkProtocol ( ) - > getSystemId ( ) , qgcApp ( ) - > toolbox ( ) - > mavlinkProtocol ( ) - > getComponentId ( ) , & message , & missionCount ) ;
_vehicle - > sendMessage ( message ) ;
_startAckTimeout ( AckMissionRequest ) ;
emit inProgressChanged ( true ) ;
// Prime write list
for ( int i = 0 ; i < _missionItems . count ( ) ; i + + ) {
_itemIndicesToWrite < < i ;
}
void MissionManager : : _retryWrite ( void )
{
qCDebug ( MissionManagerLog ) < < " _retryWrite " ;
_writeTransactionInProgress = true ;
mavlink_message_t message ;
mavlink_mission_count_t missionCount ;
_expectedSequenceNumber = 0 ;
missionCount . target_system = _vehicle - > id ( ) ;
missionCount . target_component = MAV_COMP_ID_MISSIONPLANNER ;
missionCount . count = _missionItems . count ( ) ;
@ -116,6 +100,7 @@ void MissionManager::_retryWrite(void)
@@ -116,6 +100,7 @@ void MissionManager::_retryWrite(void)
_vehicle - > sendMessage ( message ) ;
_startAckTimeout ( AckMissionRequest ) ;
emit inProgressChanged ( true ) ;
}
void MissionManager : : requestMissionItems ( void )
@ -125,7 +110,9 @@ void MissionManager::requestMissionItems(void)
@@ -125,7 +110,9 @@ void MissionManager::requestMissionItems(void)
mavlink_message_t message ;
mavlink_mission_request_list_t request ;
_retryCount = 0 ;
_requestItemRetryCount = 0 ;
_itemIndicesToRead . clear ( ) ;
_readTransactionInProgress = true ;
_clearMissionItems ( ) ;
request . target_system = _vehicle - > id ( ) ;
@ -138,24 +125,6 @@ void MissionManager::requestMissionItems(void)
@@ -138,24 +125,6 @@ void MissionManager::requestMissionItems(void)
emit inProgressChanged ( true ) ;
}
void MissionManager : : _retryRead ( void )
{
qCDebug ( MissionManagerLog ) < < " _retryRead " ;
mavlink_message_t message ;
mavlink_mission_request_list_t request ;
_clearMissionItems ( ) ;
request . target_system = _vehicle - > id ( ) ;
request . target_component = MAV_COMP_ID_MISSIONPLANNER ;
mavlink_msg_mission_request_list_encode ( qgcApp ( ) - > toolbox ( ) - > mavlinkProtocol ( ) - > getSystemId ( ) , qgcApp ( ) - > toolbox ( ) - > mavlinkProtocol ( ) - > getComponentId ( ) , & message , & request ) ;
_vehicle - > sendMessage ( message ) ;
_startAckTimeout ( AckMissionCount ) ;
}
void MissionManager : : _ackTimeout ( void )
{
AckType_t timedOutAck = _retryAck ;
@ -168,10 +137,8 @@ void MissionManager::_ackTimeout(void)
@@ -168,10 +137,8 @@ void MissionManager::_ackTimeout(void)
return ;
}
if ( ! _retrySequence ( timedOutAck ) ) {
qCDebug ( MissionManagerLog ) < < " _ackTimeout failed after max retries _retryAck:_retryCount " < < _ackTypeToString ( timedOutAck ) < < _retryCount ;
_sendError ( AckTimeoutError , QString ( " Vehicle did not respond to mission item communication: %1 " ) . arg ( _ackTypeToString ( timedOutAck ) ) ) ;
}
_finishTransaction ( false ) ;
}
void MissionManager : : _startAckTimeout ( AckType_t ack )
@ -190,11 +157,8 @@ bool MissionManager::_stopAckTimeout(AckType_t expectedAck)
@@ -190,11 +157,8 @@ bool MissionManager::_stopAckTimeout(AckType_t expectedAck)
_ackTimeoutTimer - > stop ( ) ;
if ( savedRetryAck ! = expectedAck ) {
qCDebug ( MissionManagerLog ) < < " Invalid ack sequence _retryAck:expectedAck " < < _ackTypeToString ( savedRetryAck ) < < _ackTypeToString ( expectedAck ) ;
if ( _retrySequence ( expectedAck ) ) {
_sendError ( ProtocolOrderError , QString ( " Vehicle responded incorrectly to mission item protocol sequence: %1:%2 " ) . arg ( _ackTypeToString ( savedRetryAck ) ) . arg ( _ackTypeToString ( expectedAck ) ) ) ;
}
_finishTransaction ( false ) ;
success = false ;
} else {
success = true ;
@ -219,7 +183,7 @@ void MissionManager::_readTransactionComplete(void)
@@ -219,7 +183,7 @@ void MissionManager::_readTransactionComplete(void)
_vehicle - > sendMessage ( message ) ;
emit newMissionItemsAvailable ( ) ;
emit inProgressChanged ( fals e) ;
_finishTransaction ( tru e) ;
}
void MissionManager : : _handleMissionCount ( const mavlink_message_t & message )
@ -231,24 +195,27 @@ void MissionManager::_handleMissionCount(const mavlink_message_t& message)
@@ -231,24 +195,27 @@ void MissionManager::_handleMissionCount(const mavlink_message_t& message)
}
mavlink_msg_mission_count_decode ( & message , & missionCount ) ;
qCDebug ( MissionManagerLog ) < < " _handleMissionCount count: " < < missionCount . count ;
_cMissionItems = missionCount . count ;
qCDebug ( MissionManagerLog ) < < " _handleMissionCount count: " < < _cMissionItems ;
if ( _cMissionItems = = 0 ) {
if ( missionCount . count = = 0 ) {
_readTransactionComplete ( ) ;
} else {
_requestNextMissionItem ( 0 ) ;
// Prime read list
for ( int i = 0 ; i < missionCount . count ; i + + ) {
_itemIndicesToRead < < i ;
}
_requestNextMissionItem ( ) ;
}
void MissionManager : : _requestNextMissionItem ( int sequenceNumber )
}
void MissionManager : : _requestNextMissionItem ( void )
{
qCDebug ( MissionManagerLog ) < < " _requestNextMissionItem sequenceNumber: " < < sequenceNumber ;
qCDebug ( MissionManagerLog ) < < " _requestNextMissionItem sequenceNumber: " < < _itemIndicesToRead [ 0 ] ;
if ( sequenceNumber > = _cMissionItems ) {
qCWarning ( MissionManagerLog ) < < " _requestNextMissionItem requested seqeuence number > item count sequenceNumber::_cMissionItems " < < sequenceNumber < < _cMissionItems ;
_sendError ( InternalError , QString ( " QGroundControl requested mission item outside of range (internal error): %1:%2 " ) . arg ( sequenceNumber ) . arg ( _cMissionItems ) ) ;
if ( _itemIndicesToRead . count ( ) = = 0 ) {
_sendError ( InternalError , " Internal Error: Call to Vehicle _requestNextMissionItem with no more indices to read " ) ;
return ;
}
@ -257,8 +224,7 @@ void MissionManager::_requestNextMissionItem(int sequenceNumber)
@@ -257,8 +224,7 @@ void MissionManager::_requestNextMissionItem(int sequenceNumber)
missionRequest . target_system = _vehicle - > id ( ) ;
missionRequest . target_component = MAV_COMP_ID_MISSIONPLANNER ;
missionRequest . seq = sequenceNumber ;
_expectedSequenceNumber = sequenceNumber ;
missionRequest . seq = _itemIndicesToRead [ 0 ] ;
mavlink_msg_mission_request_encode ( qgcApp ( ) - > toolbox ( ) - > mavlinkProtocol ( ) - > getSystemId ( ) , qgcApp ( ) - > toolbox ( ) - > mavlinkProtocol ( ) - > getComponentId ( ) , & message , & missionRequest ) ;
@ -278,13 +244,9 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
@@ -278,13 +244,9 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
qCDebug ( MissionManagerLog ) < < " _handleMissionItem sequenceNumber: " < < missionItem . seq ;
if ( missionItem . seq ! = _expectedSequenceNumber ) {
qCDebug ( MissionManagerLog ) < < " _handleMissionItem mission item received out of sequence expected:actual " < < _expectedSequenceNumber < < missionItem . seq ;
if ( ! _retrySequence ( AckMissionItem ) ) {
_sendError ( ItemMismatchError , QString ( " Vehicle returned incorrect mission item: %1:%2 " ) . arg ( _expectedSequenceNumber ) . arg ( missionItem . seq ) ) ;
}
return ;
}
if ( _itemIndicesToRead . contains ( missionItem . seq ) ) {
_requestItemRetryCount = 0 ;
_itemIndicesToRead . removeOne ( missionItem . seq ) ;
MissionItem * item = new MissionItem ( missionItem . seq ,
( MAV_CMD ) missionItem . command ,
@ -300,18 +262,25 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
@@ -300,18 +262,25 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
missionItem . current ,
this ) ;
_missionItems . append ( item ) ;
} else {
qCDebug ( MissionManagerLog ) < < " _handleMissionItem mission item received item index which was not requested, disregrarding: " < < missionItem . seq ;
if ( + + _requestItemRetryCount > _maxRetryCount ) {
_sendError ( RequestRangeError , QString ( " Vehicle would not send item %1 after max retries. Read from Vehicle failed. " ) . arg ( _itemIndicesToRead [ 0 ] ) ) ;
_finishTransaction ( false ) ;
return ;
}
}
int nextSequenceNumber = missionItem . seq + 1 ;
if ( nextSequenceNumber = = _cMissionItems ) {
if ( _itemIndicesToRead . count ( ) = = 0 ) {
_readTransactionComplete ( ) ;
} else {
_requestNextMissionItem ( nextSequenceNumber ) ;
_requestNextMissionItem ( ) ;
}
}
void MissionManager : : _clearMissionItems ( void )
{
_cMissionItems = 0 ;
_itemIndicesToRead . clear ( ) ;
_missionItems . clear ( ) ;
}
@ -327,16 +296,17 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message)
@@ -327,16 +296,17 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message)
qCDebug ( MissionManagerLog ) < < " _handleMissionRequest sequenceNumber: " < < missionRequest . seq ;
if ( missionRequest . seq ! = _expectedSequenceNumber ) {
qCDebug ( MissionManagerLog ) < < " _handleMissionRequest invalid sequence number requested: _expectedSequenceNumber:missionRequest.seq " < < _expectedSequenceNumber < < missionRequest . seq ;
if ( ! _retrySequence ( AckMissionRequest ) ) {
_sendError ( ItemMismatchError , QString ( " Vehicle requested incorrect mission item: %1:%2 " ) . arg ( _expectedSequenceNumber ) . arg ( missionRequest . seq ) ) ;
}
if ( ! _itemIndicesToWrite . contains ( missionRequest . seq ) ) {
if ( missionRequest . seq > _missionItems . count ( ) ) {
_sendError ( RequestRangeError , QString ( " Vehicle requested item outside range, count:request %1:%2. Send to Vehicle failed. " ) . arg ( _missionItems . count ( ) ) . arg ( missionRequest . seq ) ) ;
_finishTransaction ( false ) ;
return ;
} else {
qCDebug ( MissionManagerLog ) < < " _handleMissionRequest sequence number requested which has already been sent, sending again: " < < missionRequest . seq ;
}
} else {
_itemIndicesToWrite . removeOne ( missionRequest . seq ) ;
}
_expectedSequenceNumber + + ;
mavlink_message_t messageOut ;
mavlink_mission_item_t missionItem ;
@ -386,41 +356,31 @@ void MissionManager::_handleMissionAck(const mavlink_message_t& message)
@@ -386,41 +356,31 @@ void MissionManager::_handleMissionAck(const mavlink_message_t& message)
switch ( savedRetryAck ) {
case AckNone :
// State machine is idle. Vehicle is confused.
qCDebug ( MissionManagerLog ) < < " _handleMissionAck vehicle sent ack while state machine is idle: error: " < < _missionResultToString ( ( MAV_MISSION_RESULT ) missionAck . type ) ;
_sendError ( VehicleError , QString ( " Vehicle sent unexpected MISSION_ACK message, error: %1 " ) . arg ( _missionResultToString ( ( MAV_MISSION_RESULT ) missionAck . type ) ) ) ;
break ;
case AckMissionCount :
// MISSION_COUNT message expected
qCDebug ( MissionManagerLog ) < < " _handleMissionAck vehicle sent ack when MISSION_COUNT expected: error: " < < _missionResultToString ( ( MAV_MISSION_RESULT ) missionAck . type ) ;
if ( ! _retrySequence ( AckMissionCount ) ) {
_sendError ( VehicleError , QString ( " Vehicle returned error: %1. Partial list of mission items may have been returned. " ) . arg ( _missionResultToString ( ( MAV_MISSION_RESULT ) missionAck . type ) ) ) ;
}
_sendError ( VehicleError , QString ( " Vehicle returned error: %1. " ) . arg ( _missionResultToString ( ( MAV_MISSION_RESULT ) missionAck . type ) ) ) ;
_finishTransaction ( false ) ;
break ;
case AckMissionItem :
// MISSION_ITEM expected
qCDebug ( MissionManagerLog ) < < " _handleMissionAck vehicle sent ack when MISSION_ITEM expected: error: " < < _missionResultToString ( ( MAV_MISSION_RESULT ) missionAck . type ) ;
if ( ! _retrySequence ( AckMissionItem ) ) {
_sendError ( VehicleError , QString ( " Vehicle returned error: %1. Partial list of mission items may have been returned. " ) . arg ( _missionResultToString ( ( MAV_MISSION_RESULT ) missionAck . type ) ) ) ;
}
_finishTransaction ( false ) ;
break ;
case AckMissionRequest :
// MISSION_REQUEST is expected, or MISSION_ACK to end sequence
if ( missionAck . type = = MAV_MISSION_ACCEPTED ) {
if ( _expectedSequenceNumber = = _missionItems . count ( ) ) {
if ( _itemIndicesToWrite . count ( ) = = 0 ) {
qCDebug ( MissionManagerLog ) < < " _handleMissionAck write sequence complete " ;
emit inProgressChanged ( fals e) ;
_finishTransaction ( tru e) ;
} else {
qCDebug ( MissionManagerLog ) < < " _handleMissionAck vehicle did not reqeust all items: _expectedSequenceNumber:_missionItems.count " < < _expectedSequenceNumber < < _missionItems . count ( ) ;
if ( ! _retrySequence ( AckMissionRequest ) ) {
_sendError ( MissingRequestsError , QString ( " Vehicle did not request all items during write sequence %1:%2. Vehicle only has partial list of mission items. " ) . arg ( _expectedSequenceNumber ) . arg ( _missionItems . count ( ) ) ) ;
}
_sendError ( MissingRequestsError , QString ( " Vehicle did not request all items during write sequence, missed count %1. Vehicle only has partial list of mission items. " ) . arg ( _itemIndicesToWrite . count ( ) ) ) ;
_finishTransaction ( false ) ;
}
} else {
qCDebug ( MissionManagerLog ) < < " _handleMissionAck ack error: " < < _missionResultToString ( ( MAV_MISSION_RESULT ) missionAck . type ) ;
if ( ! _retrySequence ( AckMissionRequest ) ) {
_sendError ( VehicleError ,
QString ( " Vehicle returned error: %1 on item %2. Vehicle only has partial list of mission items. " ) . arg ( _missionResultToString ( ( MAV_MISSION_RESULT ) missionAck . type ) ) . arg ( _expectedSequenceNumber ) ) ;
}
_sendError ( VehicleError , QString ( " Vehicle returned error: %1. Vehicle only has partial list of mission items. " ) . arg ( _missionResultToString ( ( MAV_MISSION_RESULT ) missionAck . type ) ) ) ;
_finishTransaction ( false ) ;
}
break ;
}
@ -469,43 +429,9 @@ QmlObjectListModel* MissionManager::copyMissionItems(void)
@@ -469,43 +429,9 @@ QmlObjectListModel* MissionManager::copyMissionItems(void)
void MissionManager : : _sendError ( ErrorCode_t errorCode , const QString & errorMsg )
{
emit inProgressChanged ( false ) ;
emit error ( errorCode , errorMsg ) ;
}
qCDebug ( MissionManagerLog ) < < " Sending error " < < errorCode < < errorMsg ;
/// Retry the protocol sequence given the specified ack
/// @return true: sequence retried, false: out of retries
bool MissionManager : : _retrySequence ( AckType_t ackType )
{
qCDebug ( MissionManagerLog ) < < " _retrySequence ackType: " < < _ackTypeToString ( ackType ) < < " _retryCount " < < _retryCount ;
switch ( ackType ) {
case AckMissionCount :
case AckMissionItem :
if ( + + _retryCount < = _maxRetryCount ) {
// We are in the middle of a read sequence, start over
_retryRead ( ) ;
return true ;
} else {
// Read sequence failed, signal for what we have up to this point
emit newMissionItemsAvailable ( ) ;
return false ;
}
break ;
case AckMissionRequest :
if ( + + _retryCount < = _maxRetryCount ) {
// We are in the middle of a write sequence, start over
_retryWrite ( ) ;
return true ;
} else {
return false ;
}
break ;
default :
qCWarning ( MissionManagerLog ) < < " _retrySequence fell through switch: ackType: " < < _ackTypeToString ( ackType ) ;
_sendError ( InternalError , QString ( " Internal error occured during Mission Item communication: _retrySequence fell through switch: ackType: " ) . arg ( _ackTypeToString ( ackType ) ) ) ;
return false ;
}
emit error ( errorCode , errorMsg ) ;
}
QString MissionManager : : _ackTypeToString ( AckType_t ackType )
@ -578,3 +504,24 @@ QString MissionManager::_missionResultToString(MAV_MISSION_RESULT result)
@@ -578,3 +504,24 @@ QString MissionManager::_missionResultToString(MAV_MISSION_RESULT result)
return QString ( " QGC Internal Error " ) ;
}
}
void MissionManager : : _finishTransaction ( bool success )
{
if ( ! success & & _readTransactionInProgress ) {
// Read from vehicle failed, clear partial list
_missionItems . clear ( ) ;
emit newMissionItemsAvailable ( ) ;
}
_readTransactionInProgress = false ;
_writeTransactionInProgress = false ;
_itemIndicesToRead . clear ( ) ;
_itemIndicesToWrite . clear ( ) ;
emit inProgressChanged ( false ) ;
}
bool MissionManager : : inProgress ( void )
{
return _readTransactionInProgress | | _writeTransactionInProgress ;
}