Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
d2c3e365
Commit
d2c3e365
authored
Jun 27, 2014
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Switch to kErrEOF style read loop handling
parent
e2e246fe
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
78 additions
and
71 deletions
+78
-71
MockMavlinkFileServer.cc
src/qgcunittest/MockMavlinkFileServer.cc
+6
-22
QGCUASFileManager.cc
src/uas/QGCUASFileManager.cc
+71
-47
QGCUASFileManager.h
src/uas/QGCUASFileManager.h
+1
-2
No files found.
src/qgcunittest/MockMavlinkFileServer.cc
View file @
d2c3e365
...
...
@@ -69,7 +69,6 @@ void MockMavlinkFileServer::_listCommand(QGCUASFileManager::Request* request)
ackResponse
.
hdr
.
session
=
0
;
ackResponse
.
hdr
.
offset
=
request
->
hdr
.
offset
;
ackResponse
.
hdr
.
size
=
0
;
ackResponse
.
hdr
.
errCode
=
QGCUASFileManager
::
kErrNone
;
if
(
request
->
hdr
.
offset
==
0
)
{
// Requesting first batch of file names
...
...
@@ -82,12 +81,12 @@ void MockMavlinkFileServer::_listCommand(QGCUASFileManager::Request* request)
ackResponse
.
hdr
.
size
+=
cchFilename
+
1
;
bufPtr
+=
cchFilename
+
1
;
}
_emitResponse
(
&
ackResponse
);
}
else
{
// FIXME: Does not support directories that span multiple packets
_sendNak
(
QGCUASFileManager
::
kErrEOF
);
}
_emitResponse
(
&
ackResponse
);
}
/// @brief Handles Open command requests.
...
...
@@ -119,7 +118,6 @@ void MockMavlinkFileServer::_openCommand(QGCUASFileManager::Request* request)
response
.
hdr
.
opcode
=
QGCUASFileManager
::
kRspAck
;
response
.
hdr
.
session
=
_sessionId
;
response
.
hdr
.
size
=
0
;
response
.
hdr
.
errCode
=
QGCUASFileManager
::
kErrNone
;
_emitResponse
(
&
response
);
}
...
...
@@ -137,7 +135,7 @@ void MockMavlinkFileServer::_readCommand(QGCUASFileManager::Request* request)
uint32_t
readOffset
=
request
->
hdr
.
offset
;
// offset into file for reading
uint8_t
cDataBytes
=
0
;
// current number of data bytes used
if
(
readOffset
>
_readFileLength
)
{
if
(
readOffset
>
=
_readFileLength
)
{
_sendNak
(
QGCUASFileManager
::
kErrEOF
);
return
;
}
...
...
@@ -159,22 +157,10 @@ void MockMavlinkFileServer::_readCommand(QGCUASFileManager::Request* request)
Q_ASSERT
(
cDataBytes
);
response
.
hdr
.
magic
=
'f'
;
response
.
hdr
.
opcode
=
QGCUASFileManager
::
kRspAck
;
response
.
hdr
.
session
=
_sessionId
;
response
.
hdr
.
size
=
cDataBytes
;
response
.
hdr
.
offset
=
request
->
hdr
.
offset
;
if
(
readOffset
>=
_readFileLength
)
{
// Something wrong with the reading code, should not have gone past last byte
Q_ASSERT
(
readOffset
==
_readFileLength
);
// We have read all the bytes in the file
response
.
hdr
.
errCode
=
QGCUASFileManager
::
kErrNone
;
}
else
{
// There are still more bytes left to read in the file
response
.
hdr
.
errCode
=
QGCUASFileManager
::
kErrMore
;
}
response
.
hdr
.
opcode
=
QGCUASFileManager
::
kRspAck
;
_emitResponse
(
&
response
);
}
...
...
@@ -226,7 +212,6 @@ void MockMavlinkFileServer::sendMessage(mavlink_message_t message)
ackResponse
.
hdr
.
session
=
0
;
ackResponse
.
hdr
.
crc32
=
0
;
ackResponse
.
hdr
.
size
=
0
;
ackResponse
.
hdr
.
errCode
=
QGCUASFileManager
::
kErrNone
;
_emitResponse
(
&
ackResponse
);
break
;
...
...
@@ -270,7 +255,6 @@ void MockMavlinkFileServer::_sendAck(void)
ackResponse
.
hdr
.
opcode
=
QGCUASFileManager
::
kRspAck
;
ackResponse
.
hdr
.
session
=
0
;
ackResponse
.
hdr
.
size
=
0
;
ackResponse
.
hdr
.
errCode
=
QGCUASFileManager
::
kErrNone
;
_emitResponse
(
&
ackResponse
);
}
...
...
@@ -283,8 +267,8 @@ void MockMavlinkFileServer::_sendNak(QGCUASFileManager::ErrorCode error)
nakResponse
.
hdr
.
magic
=
'f'
;
nakResponse
.
hdr
.
opcode
=
QGCUASFileManager
::
kRspNak
;
nakResponse
.
hdr
.
session
=
0
;
nakResponse
.
hdr
.
size
=
0
;
nakResponse
.
hdr
.
errCode
=
error
;
nakResponse
.
hdr
.
size
=
1
;
nakResponse
.
data
[
0
]
=
error
;
_emitResponse
(
&
nakResponse
);
}
...
...
src/uas/QGCUASFileManager.cc
View file @
d2c3e365
...
...
@@ -65,6 +65,7 @@ static const quint32 crctab[] =
0xb3667a2e
,
0xc4614ab8
,
0x5d681b02
,
0x2a6f2b94
,
0xb40bbe37
,
0xc30c8ea1
,
0x5a05df1b
,
0x2d02ef8d
};
QGCUASFileManager
::
QGCUASFileManager
(
QObject
*
parent
,
UASInterface
*
uas
)
:
QObject
(
parent
),
_currentOperation
(
kCOIdle
),
...
...
@@ -74,8 +75,7 @@ QGCUASFileManager::QGCUASFileManager(QObject* parent, UASInterface* uas) :
{
bool
connected
=
connect
(
&
_ackTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
_ackTimeout
()));
Q_ASSERT
(
connected
);
Q_UNUSED
(
connected
);
Q_UNUSED
(
connected
);
// Silence retail unused variable error
}
/// @brief Calculates a 32 bit CRC for the specified request.
...
...
@@ -123,6 +123,34 @@ void QGCUASFileManager::_openAckResponse(Request* openAck)
_sendRequest
(
&
request
);
}
/// @brief Closes out a read session by writing the file and doing cleanup.
/// @param success true: successful download completion, false: error during download
void
QGCUASFileManager
::
_closeReadSession
(
bool
success
)
{
if
(
success
)
{
QString
downloadFilePath
=
_readFileDownloadDir
.
absoluteFilePath
(
_readFileDownloadFilename
);
QFile
file
(
downloadFilePath
);
if
(
!
file
.
open
(
QIODevice
::
WriteOnly
|
QIODevice
::
Truncate
))
{
_emitErrorMessage
(
tr
(
"Unable to open local file for writing (%1)"
).
arg
(
downloadFilePath
));
return
;
}
qint64
bytesWritten
=
file
.
write
((
const
char
*
)
_readFileAccumulator
,
_readFileAccumulator
.
length
());
if
(
bytesWritten
!=
_readFileAccumulator
.
length
())
{
file
.
close
();
_emitErrorMessage
(
tr
(
"Unable to write data to local file (%1)"
).
arg
(
downloadFilePath
));
return
;
}
file
.
close
();
_emitStatusMessage
(
tr
(
"Download complete '%1'"
).
arg
(
downloadFilePath
));
}
// Close the open session
_sendTerminateCommand
();
}
/// @brief Respond to the Ack associated with the Read command.
void
QGCUASFileManager
::
_readAckResponse
(
Request
*
readAck
)
{
...
...
@@ -142,8 +170,8 @@ void QGCUASFileManager::_readAckResponse(Request* readAck)
_readFileAccumulator
.
append
((
const
char
*
)
readAck
->
data
,
readAck
->
hdr
.
size
);
if
(
readAck
->
hdr
.
errCode
==
kErrMore
)
{
//
S
till more data to read, send next read request
if
(
readAck
->
hdr
.
size
==
sizeof
(
readAck
->
data
)
)
{
//
Possibly s
till more data to read, send next read request
_currentOperation
=
kCORead
;
...
...
@@ -157,32 +185,9 @@ void QGCUASFileManager::_readAckResponse(Request* readAck)
_sendRequest
(
&
request
);
}
else
{
// We're at the end of the file, we can write it out now
Q_ASSERT
(
readAck
->
hdr
.
errCode
==
kErrNone
);
// We only receieved a partial buffer back. These means we are at EOF
_currentOperation
=
kCOIdle
;
QString
downloadFilePath
=
_readFileDownloadDir
.
absoluteFilePath
(
_readFileDownloadFilename
);
QFile
file
(
downloadFilePath
);
if
(
!
file
.
open
(
QIODevice
::
WriteOnly
|
QIODevice
::
Truncate
))
{
_emitErrorMessage
(
tr
(
"Unable to open local file for writing (%1)"
).
arg
(
downloadFilePath
));
return
;
}
qint64
bytesWritten
=
file
.
write
((
const
char
*
)
_readFileAccumulator
,
_readFileAccumulator
.
length
());
if
(
bytesWritten
!=
_readFileAccumulator
.
length
())
{
file
.
close
();
_emitErrorMessage
(
tr
(
"Unable to write data to local file (%1)"
).
arg
(
downloadFilePath
));
return
;
}
file
.
close
();
_emitStatusMessage
(
tr
(
"Download complete '%1'"
).
arg
(
downloadFilePath
));
// Close the open session
_sendTerminateCommand
();
_closeReadSession
(
true
/* success */
);
}
}
...
...
@@ -216,34 +221,33 @@ void QGCUASFileManager::_listAckResponse(Request* listAck)
return
;
}
// Returned names are prepended with D for directory or F for file
// Returned names are prepended with D for directory, F for file, U for unknown
QString
s
(
ptr
+
1
);
if
(
*
ptr
==
'D'
)
{
s
.
append
(
'/'
);
}
else
if
(
*
ptr
!=
'F'
)
{
_currentOperation
=
kCOIdle
;
_emitErrorMessage
(
tr
(
"Unknown prefix list entry: '%1'"
).
arg
(
ptr
));
return
;
}
// put it in the view
_emitStatusMessage
(
s
);
if
(
*
ptr
==
'F'
||
*
ptr
==
'D'
)
{
// put it in the view
_emitStatusMessage
(
s
);
}
// account for the name + NUL
offset
+=
nlen
+
1
;
cListEntries
++
;
}
if
(
listAck
->
hdr
.
errCode
==
kErrMore
)
{
// Still more data to read, send next list request
if
(
listAck
->
hdr
.
size
==
0
)
{
// Directory is empty, we're done
Q_ASSERT
(
listAck
->
hdr
.
opcode
==
kRspAck
);
_currentOperation
=
kCOIdle
;
}
else
{
// Possibly more entries to come, need to keep trying till we get EOF
_currentOperation
=
kCOList
;
_listOffset
+=
cListEntries
;
_sendListCommand
();
}
else
{
// We've gotten the last list entries we can go back to idle
Q_ASSERT
(
listAck
->
hdr
.
errCode
==
kErrNone
);
_currentOperation
=
kCOIdle
;
}
}
...
...
@@ -256,6 +260,8 @@ void QGCUASFileManager::receiveMessage(LinkInterface* link, mavlink_message_t me
return
;
}
_clearAckTimeout
();
mavlink_encapsulated_data_t
data
;
mavlink_msg_encapsulated_data_decode
(
&
message
,
&
data
);
Request
*
request
=
(
Request
*
)
&
data
.
data
[
0
];
...
...
@@ -263,7 +269,6 @@ void QGCUASFileManager::receiveMessage(LinkInterface* link, mavlink_message_t me
// FIXME: Check CRC
if
(
request
->
hdr
.
opcode
==
kRspAck
)
{
_clearAckTimeout
();
switch
(
_currentOperation
)
{
case
kCOIdle
:
...
...
@@ -293,13 +298,32 @@ void QGCUASFileManager::receiveMessage(LinkInterface* link, mavlink_message_t me
break
;
}
}
else
if
(
request
->
hdr
.
opcode
==
kRspNak
)
{
_clearAckTimeout
();
_emitErrorMessage
(
tr
(
"Nak received, error: %1"
).
arg
(
request
->
hdr
.
errCode
));
Q_ASSERT
(
request
->
hdr
.
size
==
1
);
// Should only have one byte of error code
OperationState
previousOperation
=
_currentOperation
;
uint8_t
errorCode
=
request
->
data
[
0
];
_currentOperation
=
kCOIdle
;
if
(
previousOperation
==
kCOList
&&
errorCode
==
kErrEOF
)
{
// This is not an error, just the end of the read loop
return
;
}
else
if
(
previousOperation
==
kCORead
&&
errorCode
==
kErrEOF
)
{
// This is not an error, just the end of the read loop
_closeReadSession
(
true
/* success */
);
return
;
}
else
{
// Generic Nak handling
if
(
previousOperation
==
kCORead
)
{
// Nak error during read loop, download failed
_closeReadSession
(
false
/* failure */
);
}
_emitErrorMessage
(
tr
(
"Nak received, error: %1"
).
arg
(
errorString
(
request
->
data
[
0
])));
}
}
else
{
// Note that we don't change our operation state. If something goes wrong beyond this, the operation
// will time out.
_emitErrorMessage
(
tr
(
"Unknown opcode returned server: %1"
).
arg
(
request
->
hdr
.
opcode
));
_emitErrorMessage
(
tr
(
"Unknown opcode returned
from
server: %1"
).
arg
(
request
->
hdr
.
opcode
));
}
}
...
...
src/uas/QGCUASFileManager.h
View file @
d2c3e365
...
...
@@ -60,7 +60,6 @@ protected:
uint8_t
size
;
///> Size of data
uint32_t
crc32
;
///> CRC for entire Request structure, with crc32 set to 0
uint32_t
offset
;
///> Offsets for List and Read commands
uint8_t
errCode
;
///> Error code from Ack and Naks (ignored for commands)
};
struct
Request
...
...
@@ -95,7 +94,6 @@ protected:
enum
ErrorCode
{
kErrNone
,
kErrMore
,
kErrNoRequest
,
kErrNoSession
,
kErrSequence
,
...
...
@@ -137,6 +135,7 @@ protected:
void
_listAckResponse
(
Request
*
listAck
);
void
_sendListCommand
(
void
);
void
_sendTerminateCommand
(
void
);
void
_closeReadSession
(
bool
success
);
static
quint32
crc32
(
Request
*
request
,
unsigned
state
=
0
);
static
QString
errorString
(
uint8_t
errorCode
);
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment