1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#ifndef MAVLinkLogManager_H
#define MAVLinkLogManager_H
#include <QObject>
#include "QmlObjectListModel.h"
#include "QGCLoggingCategory.h"
#include "QGCToolbox.h"
#include "Vehicle.h"
Q_DECLARE_LOGGING_CATEGORY(MAVLinkLogManagerLog)
class QNetworkAccessManager;
class MAVLinkLogManager;
//-----------------------------------------------------------------------------
class MAVLinkLogFiles : public QObject
{
Q_OBJECT
public:
MAVLinkLogFiles (MAVLinkLogManager* manager, const QString& filePath, bool newFile = false);
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(quint32 size READ size NOTIFY sizeChanged)
Q_PROPERTY(bool selected READ selected WRITE setSelected NOTIFY selectedChanged)
Q_PROPERTY(bool uploading READ uploading NOTIFY uploadingChanged)
Q_PROPERTY(qreal progress READ progress NOTIFY progressChanged)
Q_PROPERTY(bool writing READ writing NOTIFY writingChanged)
Q_PROPERTY(bool uploaded READ uploaded NOTIFY uploadedChanged)
QString name () { return _name; }
quint32 size () { return _size; }
bool selected () { return _selected; }
bool uploading () { return _uploading; }
qreal progress () { return _progress; }
bool writing () { return _writing; }
bool uploaded () { return _uploaded; }
void setSelected (bool selected);
void setUploading (bool uploading);
void setProgress (qreal progress);
void setWriting (bool writing);
void setSize (quint32 size);
void setUploaded (bool uploaded);
signals:
void sizeChanged ();
void selectedChanged ();
void uploadingChanged ();
void progressChanged ();
void writingChanged ();
void uploadedChanged ();
private:
MAVLinkLogManager* _manager;
QString _name;
quint32 _size;
bool _selected;
bool _uploading;
qreal _progress;
bool _writing;
bool _uploaded;
};
//-----------------------------------------------------------------------------
class MAVLinkLogProcessor
{
public:
MAVLinkLogProcessor();
~MAVLinkLogProcessor();
void close ();
bool valid ();
bool create (MAVLinkLogManager *manager, const QString path, uint8_t id);
MAVLinkLogFiles* record () { return _record; }
QString fileName () { return _fileName; }
bool processStreamData(uint16_t _sequence, uint8_t first_message, QByteArray data);
private:
bool _checkSequence(uint16_t seq, int &num_drops);
QByteArray _writeUlogMessage(QByteArray &data);
void _writeData(void* data, int len);
private:
FILE* _fd;
quint32 _written;
int _sequence;
int _numDrops;
bool _gotHeader;
bool _error;
QByteArray _ulogMessage;
QString _fileName;
MAVLinkLogFiles* _record;
};
//-----------------------------------------------------------------------------
class MAVLinkLogManager : public QGCTool
{
Q_OBJECT
public:
MAVLinkLogManager (QGCApplication* app);
~MAVLinkLogManager ();
Q_PROPERTY(QString emailAddress READ emailAddress WRITE setEmailAddress NOTIFY emailAddressChanged)
Q_PROPERTY(QString description READ description WRITE setDescription NOTIFY descriptionChanged)
Q_PROPERTY(QString uploadURL READ uploadURL WRITE setUploadURL NOTIFY uploadURLChanged)
Q_PROPERTY(QString feedback READ feedback WRITE setFeedback NOTIFY feedbackChanged)
Q_PROPERTY(QString videoURL READ videoURL WRITE setVideoURL NOTIFY videoURLChanged)
Q_PROPERTY(bool enableAutoUpload READ enableAutoUpload WRITE setEnableAutoUpload NOTIFY enableAutoUploadChanged)
Q_PROPERTY(bool enableAutoStart READ enableAutoStart WRITE setEnableAutoStart NOTIFY enableAutoStartChanged)
Q_PROPERTY(bool deleteAfterUpload READ deleteAfterUpload WRITE setDeleteAfterUpload NOTIFY deleteAfterUploadChanged)
Q_PROPERTY(bool publicLog READ publicLog WRITE setPublicLog NOTIFY publicLogChanged)
Q_PROPERTY(bool uploading READ uploading NOTIFY uploadingChanged)
Q_PROPERTY(bool logRunning READ logRunning NOTIFY logRunningChanged)
Q_PROPERTY(bool canStartLog READ canStartLog NOTIFY canStartLogChanged)
Q_PROPERTY(QmlObjectListModel* logFiles READ logFiles NOTIFY logFilesChanged)
Q_PROPERTY(int windSpeed READ windSpeed WRITE setWindSpeed NOTIFY windSpeedChanged)
Q_PROPERTY(QString rating READ rating WRITE setRating NOTIFY ratingChanged)
Q_INVOKABLE void uploadLog ();
Q_INVOKABLE void deleteLog ();
Q_INVOKABLE void cancelUpload ();
Q_INVOKABLE void startLogging ();
Q_INVOKABLE void stopLogging ();
QString emailAddress () { return _emailAddress; }
QString description () { return _description; }
QString uploadURL () { return _uploadURL; }
QString feedback () { return _feedback; }
QString videoURL () { return _videoURL; }
bool enableAutoUpload () { return _enableAutoUpload; }
bool enableAutoStart () { return _enableAutoStart; }
bool uploading ();
bool logRunning () { return _logRunning; }
bool canStartLog () { return _vehicle != NULL; }
bool deleteAfterUpload () { return _deleteAfterUpload; }
bool publicLog () { return _publicLog; }
int windSpeed () { return _windSpeed; }
QString rating () { return _rating; }
QmlObjectListModel* logFiles () { return &_logFiles; }
void setEmailAddress (QString email);
void setDescription (QString description);
void setUploadURL (QString url);
void setFeedback (QString feedback);
void setVideoURL (QString url);
void setEnableAutoUpload (bool enable);
void setEnableAutoStart (bool enable);
void setDeleteAfterUpload(bool enable);
void setWindSpeed (int speed);
void setRating (QString rate);
void setPublicLog (bool publicLog);
// Override from QGCTool
void setToolbox (QGCToolbox *toolbox);
signals:
void emailAddressChanged ();
void descriptionChanged ();
void uploadURLChanged ();
void feedbackChanged ();
void enableAutoUploadChanged ();
void enableAutoStartChanged ();
void logFilesChanged ();
void selectedCountChanged ();
void uploadingChanged ();
void readyRead (QByteArray data);
void failed ();
void succeed ();
void abortUpload ();
void logRunningChanged ();
void canStartLogChanged ();
void deleteAfterUploadChanged ();
void windSpeedChanged ();
void ratingChanged ();
void videoURLChanged ();
void publicLogChanged ();
private slots:
void _uploadFinished ();
void _dataAvailable ();
void _uploadProgress (qint64 bytesSent, qint64 bytesTotal);
void _activeVehicleChanged (Vehicle* vehicle);
void _mavlinkLogData (Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked);
void _armedChanged (bool armed);
void _mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
private:
bool _sendLog (const QString& logFile);
bool _processUploadResponse (int http_code, QByteArray &data);
bool _createNewLog ();
int _getFirstSelected ();
void _insertNewLog (MAVLinkLogFiles* newLog);
void _deleteLog (MAVLinkLogFiles* log);
void _discardLog ();
QString _makeFilename (const QString& baseName);
private:
QString _description;
QString _emailAddress;
QString _uploadURL;
QString _feedback;
QString _logPath;
QString _videoURL;
bool _enableAutoUpload;
bool _enableAutoStart;
QNetworkAccessManager* _nam;
QmlObjectListModel _logFiles;
MAVLinkLogFiles* _currentLogfile;
Vehicle* _vehicle;
bool _logRunning;
bool _loggingDisabled;
MAVLinkLogProcessor* _logProcessor;
bool _deleteAfterUpload;
int _windSpeed;
QString _rating;
bool _publicLog;
};
#endif