@ -29,12 +29,27 @@
@@ -29,12 +29,27 @@
QGC_LOGGING_CATEGORY ( MockLinkMissionItemHandlerLog , " MockLinkMissionItemHandlerLog " )
MockLinkMissionItemHandler : : MockLinkMissionItemHandler ( MockLink * mockLink )
: QObject ( mockLink )
, _mockLink ( mockLink )
: _mockLink ( mockLink )
, _missionItemResponseTimer ( NULL )
, _failureMode ( FailNone )
{
Q_ASSERT ( mockLink ) ;
}
MockLinkMissionItemHandler : : ~ MockLinkMissionItemHandler ( )
{
}
void MockLinkMissionItemHandler : : _startMissionItemResponseTimer ( void )
{
if ( ! _missionItemResponseTimer ) {
_missionItemResponseTimer = new QTimer ( ) ;
connect ( _missionItemResponseTimer , & QTimer : : timeout , this , & MockLinkMissionItemHandler : : _missionItemResponseTimeout ) ;
}
_missionItemResponseTimer - > start ( 500 ) ;
}
bool MockLinkMissionItemHandler : : handleMessage ( const mavlink_message_t & msg )
{
switch ( msg . msgid ) {
@ -78,21 +93,29 @@ void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message
@@ -78,21 +93,29 @@ void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message
{
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _handleMissionRequestList read sequence " ;
mavlink_mission_request_list_t request ;
mavlink_msg_mission_request_list_decode ( & msg , & request ) ;
Q_ASSERT ( request . target_system = = _mockLink - > vehicleId ( ) ) ;
mavlink_message_t responseMsg ;
if ( _failureMode ! = FailReadRequestListNoResponse ) {
mavlink_mission_request_list_t request ;
mavlink_msg_mission_request_list_decode ( & msg , & request ) ;
Q_ASSERT ( request . target_system = = _mockLink - > vehicleId ( ) ) ;
mavlink_message_t responseMsg ;
mavlink_msg_mission_count_pack ( _mockLink - > vehicleId ( ) ,
MAV_COMP_ID_MISSIONPLANNER ,
& responseMsg , // Outgoing message
msg . sysid , // Target is original sender
msg . compid , // Target is original sender
_missionItems . count ( ) ) ; // Number of mission items
_mockLink - > respondWithMavlinkMessage ( responseMsg ) ;
} else {
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _handleMissionRequestList not responding due to failure mode " ;
}
mavlink_msg_mission_count_pack ( _mockLink - > vehicleId ( ) ,
MAV_COMP_ID_MISSIONPLANNER ,
& responseMsg , // Outgoing message
msg . sysid , // Target is original sender
msg . compid , // Target is original sender
_missionItems . count ( ) ) ; // Number of mission items
_mockLink - > respondWithMavlinkMessage ( responseMsg ) ;
if ( _failureFirstTimeOnly ) {
_failureMode = FailNone ;
}
}
void MockLinkMissionItemHandler : : _handleMissionRequest ( const mavlink_message_t & msg )
@ -106,29 +129,50 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t&
@@ -106,29 +129,50 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t&
Q_ASSERT ( request . target_system = = _mockLink - > vehicleId ( ) ) ;
Q_ASSERT ( request . seq < _missionItems . count ( ) ) ;
mavlink_message_t responseMsg ;
mavlink_mission_item_t item = _missionItems [ request . seq ] ;
if ( ( _failureMode = = FailReadRequest0NoResponse & & request . seq ! = 0 ) | |
( _failureMode = = FailReadRequest1NoResponse & & request . seq ! = 1 ) ) {
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _handleMissionRequest not responding due to failure mode " ;
} else {
// FIXME: Track whether all items are requested, or requested in sequence
if ( ( _failureMode = = FailReadRequest0IncorrectSequence & & request . seq = = 0 ) | |
( _failureMode = = FailReadRequest1IncorrectSequence & & request . seq = = 1 ) ) {
// Send back the incorrect sequence number
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _handleMissionRequest sending bad sequence number " ;
request . seq + + ;
}
if ( ( _failureMode = = FailReadRequest0ErrorAck & & request . seq = = 0 ) | |
( _failureMode = = FailReadRequest1ErrorAck & & request . seq = = 1 ) ) {
_sendAck ( MAV_MISSION_ERROR ) ;
} else {
mavlink_message_t responseMsg ;
mavlink_mission_item_t item = _missionItems [ request . seq ] ;
mavlink_msg_mission_item_pack ( _mockLink - > vehicleId ( ) ,
MAV_COMP_ID_MISSIONPLANNER ,
& responseMsg , // Outgoing message
msg . sysid , // Target is original sender
msg . compid , // Target is original sender
request . seq , // Index of mission item being sent
item . frame ,
item . command ,
item . current ,
item . autocontinue ,
item . param1 , item . param2 , item . param3 , item . param4 ,
item . x , item . y , item . z ) ;
_mockLink - > respondWithMavlinkMessage ( responseMsg ) ;
}
}
mavlink_msg_mission_item_pack ( _mockLink - > vehicleId ( ) ,
MAV_COMP_ID_MISSIONPLANNER ,
& responseMsg , // Outgoing message
msg . sysid , // Target is original sender
msg . compid , // Target is original sender
request . seq , // Index of mission item being sent
item . frame ,
item . command ,
item . current ,
item . autocontinue ,
item . param1 , item . param2 , item . param3 , item . param4 ,
item . x , item . y , item . z ) ;
_mockLink - > respondWithMavlinkMessage ( responseMsg ) ;
if ( _failureFirstTimeOnly ) {
_failureMode = FailNone ;
}
}
void MockLinkMissionItemHandler : : _handleMissionCount ( const mavlink_message_t & msg )
{
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _handleMissionCount write sequence " ;
mavlink_mission_count_t missionCount ;
mavlink_msg_mission_count_decode ( & msg , & missionCount ) ;
@ -137,12 +181,12 @@ void MockLinkMissionItemHandler::_handleMissionCount(const mavlink_message_t& ms
@@ -137,12 +181,12 @@ void MockLinkMissionItemHandler::_handleMissionCount(const mavlink_message_t& ms
_writeSequenceCount = missionCount . count ;
Q_ASSERT ( _writeSequenceCount > = 0 ) ;
// FIXME: Set up a timer for a failed write sequence
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _handleMissionCount write sequence _writeSequenceCount: " < < _writeSequenceCount ;
_missionItems . clear ( ) ;
if ( _writeSequenceCount = = 0 ) {
// FIXME: NYI
_sendAck ( MAV_MISSION_ACCEPTED ) ;
} else {
_writeSequenceIndex = 0 ;
_requestNextMissionItem ( _writeSequenceIndex ) ;
@ -151,31 +195,68 @@ void MockLinkMissionItemHandler::_handleMissionCount(const mavlink_message_t& ms
@@ -151,31 +195,68 @@ void MockLinkMissionItemHandler::_handleMissionCount(const mavlink_message_t& ms
void MockLinkMissionItemHandler : : _requestNextMissionItem ( int sequenceNumber )
{
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _requestNextMissionItem write sequence sequenceNumber: " < < sequenceNumber ;
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _requestNextMissionItem write sequence sequenceNumber: " < < sequenceNumber < < " _failureMode: " < < _failureMode ;
if ( sequenceNumber > = _writeSequenceCount ) {
qCWarning ( MockLinkMissionItemHandlerLog ) < < " _requestNextMissionItem requested seqeuence number > write count sequenceNumber::_writeSequenceCount " < < sequenceNumber < < _writeSequenceCount ;
return ;
if ( ( _failureMode = = FailWriteRequest0NoResponse & & sequenceNumber = = 0 ) | |
( _failureMode = = FailWriteRequest1NoResponse & & sequenceNumber = = 1 ) ) {
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _requestNextMissionItem not responding due to failure mode " ;
} else {
if ( sequenceNumber > = _writeSequenceCount ) {
qCWarning ( MockLinkMissionItemHandlerLog ) < < " _requestNextMissionItem requested seqeuence number > write count sequenceNumber::_writeSequenceCount " < < sequenceNumber < < _writeSequenceCount ;
return ;
}
if ( ( _failureMode = = FailWriteRequest0IncorrectSequence & & sequenceNumber = = 0 ) | |
( _failureMode = = FailWriteRequest1IncorrectSequence & & sequenceNumber = = 1 ) ) {
sequenceNumber + + ;
}
if ( ( _failureMode = = FailWriteRequest0ErrorAck & & sequenceNumber = = 0 ) | |
( _failureMode = = FailWriteRequest1ErrorAck & & sequenceNumber = = 1 ) ) {
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _requestNextMissionItem sending ack error due to failure mode " ;
_sendAck ( MAV_MISSION_ERROR ) ;
} else {
mavlink_message_t message ;
mavlink_mission_request_t missionRequest ;
missionRequest . target_system = MAVLinkProtocol : : instance ( ) - > getSystemId ( ) ;
missionRequest . target_component = MAVLinkProtocol : : instance ( ) - > getComponentId ( ) ;
missionRequest . seq = sequenceNumber ;
mavlink_msg_mission_request_encode ( _mockLink - > vehicleId ( ) , MAV_COMP_ID_MISSIONPLANNER , & message , & missionRequest ) ;
_mockLink - > respondWithMavlinkMessage ( message ) ;
// If response with Mission Item doesn't come before timer fires it's an error
_startMissionItemResponseTimer ( ) ;
}
}
mavlink_message_t message ;
mavlink_mission_request_t missionRequest ;
if ( _failureFirstTimeOnly ) {
_failureMode = FailNone ;
}
}
void MockLinkMissionItemHandler : : _sendAck ( MAV_MISSION_RESULT ackType )
{
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _sendAck write sequence complete ackType: " < < ackType ;
mavlink_message_t message ;
mavlink_mission_ack_t missionAck ;
missionRequest . target_system = MAVLinkProtocol : : instance ( ) - > getSystemId ( ) ;
missionRequest . target_component = MAVLinkProtocol : : instance ( ) - > getComponentId ( ) ;
missionRequest . seq = sequenceNumber ;
missionAck . target_system = MAVLinkProtocol : : instance ( ) - > getSystemId ( ) ;
missionAck . target_component = MAVLinkProtocol : : instance ( ) - > getComponentId ( ) ;
missionAck . type = ackType ;
mavlink_msg_mission_request_encode ( _mockLink - > vehicleId ( ) , MAV_COMP_ID_MISSIONPLANNER , & message , & missionRequest ) ;
mavlink_msg_mission_ack _encode ( _mockLink - > vehicleId ( ) , MAV_COMP_ID_MISSIONPLANNER , & message , & missionAck ) ;
_mockLink - > respondWithMavlinkMessage ( message ) ;
// FIXME: Timeouts
}
void MockLinkMissionItemHandler : : _handleMissionItem ( const mavlink_message_t & msg )
{
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _handleMissionItem write sequence " ;
_missionItemResponseTimer - > stop ( ) ;
mavlink_mission_item_t missionItem ;
mavlink_msg_mission_item_decode ( & msg , & missionItem ) ;
@ -187,21 +268,61 @@ void MockLinkMissionItemHandler::_handleMissionItem(const mavlink_message_t& msg
@@ -187,21 +268,61 @@ void MockLinkMissionItemHandler::_handleMissionItem(const mavlink_message_t& msg
_missionItems [ missionItem . seq ] = missionItem ;
// FIXME: Timeouts
_writeSequenceIndex + + ;
if ( _writeSequenceIndex < _writeSequenceCount ) {
_requestNextMissionItem ( _writeSequenceIndex ) ;
if ( _failureMode = = FailWriteFinalAckMissingRequests & & _writeSequenceIndex = = 3 ) {
// Send MAV_MISSION_ACCPETED ack too early
_sendAck ( MAV_MISSION_ACCEPTED ) ;
} else {
_requestNextMissionItem ( _writeSequenceIndex ) ;
}
} else {
qCDebug ( MockLinkMissionItemHandlerLog ) < < " _handleMissionItem sending final ack, write sequence complete " ;
mavlink_message_t message ;
mavlink_mission_ack_t missionAck ;
missionAck . target_system = MAVLinkProtocol : : instance ( ) - > getSystemId ( ) ;
missionAck . target_component = MAVLinkProtocol : : instance ( ) - > getComponentId ( ) ;
missionAck . type = MAV_MISSION_ACCEPTED ;
mavlink_msg_mission_ack_encode ( _mockLink - > vehicleId ( ) , MAV_COMP_ID_MISSIONPLANNER , & message , & missionAck ) ;
_mockLink - > respondWithMavlinkMessage ( message ) ;
if ( _failureMode ! = FailWriteFinalAckNoResponse ) {
MAV_MISSION_RESULT ack = MAV_MISSION_ACCEPTED ;
if ( _failureMode = = FailWriteFinalAckErrorAck ) {
ack = MAV_MISSION_ERROR ;
}
_sendAck ( ack ) ;
}
}
if ( _failureFirstTimeOnly ) {
_failureMode = FailNone ;
}
}
void MockLinkMissionItemHandler : : _missionItemResponseTimeout ( void )
{
qWarning ( ) < < " Timeout waiting for next MISSION_ITEM " ;
Q_ASSERT ( false ) ;
}
void MockLinkMissionItemHandler : : sendUnexpectedMissionAck ( MAV_MISSION_RESULT ackType )
{
_sendAck ( ackType ) ;
}
void MockLinkMissionItemHandler : : sendUnexpectedMissionItem ( void )
{
// FIXME: NYI
Q_ASSERT ( false ) ;
}
void MockLinkMissionItemHandler : : sendUnexpectedMissionRequest ( void )
{
// FIXME: NYI
Q_ASSERT ( false ) ;
}
void MockLinkMissionItemHandler : : setMissionItemFailureMode ( FailureMode_t failureMode , bool firstTimeOnly )
{
_failureFirstTimeOnly = firstTimeOnly ;
_failureMode = failureMode ;
}
void MockLinkMissionItemHandler : : shutdown ( void )
{
if ( _missionItemResponseTimer ) {
delete _missionItemResponseTimer ;
}
}