Commit 51e1fe0d authored by Gus Grubba's avatar Gus Grubba

Updated MAVLink logging to the new “flightreport" form upload.

parent 36ce0c1d
......@@ -21,16 +21,23 @@
QGC_LOGGING_CATEGORY(MAVLinkLogManagerLog, "MAVLinkLogManagerLog")
static const char* kEmailAddressKey = "MAVLinkLogEmail";
static const char* kDescriptionsKey = "MAVLinkLogDescription";
static const char* kMAVLinkLogGroup = "MAVLinkLogGroup";
static const char* kEmailAddressKey = "Email";
static const char* kDescriptionsKey = "Description";
static const char* kDefaultDescr = "QGroundControl Session";
static const char* kPx4URLKey = "MAVLinkLogURL";
static const char* kPx4URLKey = "LogURL";
static const char* kDefaultPx4URL = "http://logs.px4.io/upload";
static const char* kEnableAutoUploadKey = "EnableAutoUploadKey";
static const char* kEnableAutoStartKey = "EnableAutoStartKey";
static const char* kEnableDeletetKey = "EnableDeleteKey";
static const char* kEnableAutoUploadKey = "EnableAutoUpload";
static const char* kEnableAutoStartKey = "EnableAutoStart";
static const char* kEnableDeletetKey = "EnableDelete";
static const char* kUlogExtension = ".ulg";
static const char* kSidecarExtension = ".uploaded";
static const char* kVideoURLKey = "VideoURL";
static const char* kWindSpeedKey = "WindSpeed";
static const char* kRateKey = "RateKey";
static const char* kPublicLogKey = "PublicLog";
static const char* kFeedback = "feedback";
static const char* kVideoURL = "videoUrl";
//-----------------------------------------------------------------------------
MAVLinkLogFiles::MAVLinkLogFiles(MAVLinkLogManager* manager, const QString& filePath, bool newFile)
......@@ -299,15 +306,22 @@ MAVLinkLogManager::MAVLinkLogManager(QGCApplication* app)
, _loggingDisabled(false)
, _logProcessor(NULL)
, _deleteAfterUpload(false)
, _windSpeed(-1)
, _publicLog(false)
{
//-- Get saved settings
QSettings settings;
settings.beginGroup(kMAVLinkLogGroup);
setEmailAddress(settings.value(kEmailAddressKey, QString()).toString());
setDescription(settings.value(kDescriptionsKey, QString(kDefaultDescr)).toString());
setUploadURL(settings.value(kPx4URLKey, QString(kDefaultPx4URL)).toString());
setVideoURL(settings.value(kVideoURLKey, QString()).toString());
setEnableAutoUpload(settings.value(kEnableAutoUploadKey, true).toBool());
setEnableAutoStart(settings.value(kEnableAutoStartKey, true).toBool());
setDeleteAfterUpload(settings.value(kEnableDeletetKey, false).toBool());
setWindSpeed(settings.value(kWindSpeedKey, -1).toInt());
setRating(settings.value(kRateKey, "notset").toString());
setPublicLog(settings.value(kPublicLogKey, true).toBool());
//-- Logging location
_logPath = QStandardPaths::writableLocation(QStandardPaths::AppDataLocation);
_logPath += "/MAVLinkLogs";
......@@ -353,6 +367,7 @@ MAVLinkLogManager::setEmailAddress(QString email)
{
_emailAddress = email;
QSettings settings;
settings.beginGroup(kMAVLinkLogGroup);
settings.setValue(kEmailAddressKey, email);
emit emailAddressChanged();
}
......@@ -363,6 +378,7 @@ MAVLinkLogManager::setDescription(QString description)
{
_description = description;
QSettings settings;
settings.beginGroup(kMAVLinkLogGroup);
settings.setValue(kDescriptionsKey, description);
emit descriptionChanged();
}
......@@ -376,16 +392,37 @@ MAVLinkLogManager::setUploadURL(QString url)
_uploadURL = kDefaultPx4URL;
}
QSettings settings;
settings.beginGroup(kMAVLinkLogGroup);
settings.setValue(kPx4URLKey, _uploadURL);
emit uploadURLChanged();
}
//-----------------------------------------------------------------------------
void
MAVLinkLogManager::setFeedback(QString fb)
{
_feedback = fb;
emit feedbackChanged();
}
//-----------------------------------------------------------------------------
void
MAVLinkLogManager::setVideoURL(QString url)
{
_videoURL = url;
QSettings settings;
settings.beginGroup(kMAVLinkLogGroup);
settings.setValue(kVideoURLKey, url);
emit videoURLChanged();
}
//-----------------------------------------------------------------------------
void
MAVLinkLogManager::setEnableAutoUpload(bool enable)
{
_enableAutoUpload = enable;
QSettings settings;
settings.beginGroup(kMAVLinkLogGroup);
settings.setValue(kEnableAutoUploadKey, enable);
emit enableAutoUploadChanged();
}
......@@ -396,6 +433,7 @@ MAVLinkLogManager::setEnableAutoStart(bool enable)
{
_enableAutoStart = enable;
QSettings settings;
settings.beginGroup(kMAVLinkLogGroup);
settings.setValue(kEnableAutoStartKey, enable);
emit enableAutoStartChanged();
}
......@@ -406,10 +444,44 @@ MAVLinkLogManager::setDeleteAfterUpload(bool enable)
{
_deleteAfterUpload = enable;
QSettings settings;
settings.beginGroup(kMAVLinkLogGroup);
settings.setValue(kEnableDeletetKey, enable);
emit deleteAfterUploadChanged();
}
//-----------------------------------------------------------------------------
void
MAVLinkLogManager::setWindSpeed(int speed)
{
_windSpeed = speed;
QSettings settings;
settings.beginGroup(kMAVLinkLogGroup);
settings.setValue(kWindSpeedKey, speed);
emit windSpeedChanged();
}
//-----------------------------------------------------------------------------
void
MAVLinkLogManager::setRating(QString rate)
{
_rating = rate;
QSettings settings;
settings.beginGroup(kMAVLinkLogGroup);
settings.setValue(kRateKey, rate);
emit ratingChanged();
}
//-----------------------------------------------------------------------------
void
MAVLinkLogManager::setPublicLog(bool pub)
{
_publicLog = pub;
QSettings settings;
settings.beginGroup(kMAVLinkLogGroup);
settings.setValue(kPublicLogKey, pub);
emit publicLogChanged();
}
//-----------------------------------------------------------------------------
bool
MAVLinkLogManager::uploading()
......@@ -619,17 +691,41 @@ MAVLinkLogManager::_sendLog(const QString& logFile)
QHttpMultiPart* multiPart = new QHttpMultiPart(QHttpMultiPart::FormDataType);
QHttpPart emailPart = create_form_part("email", _emailAddress);
QHttpPart descriptionPart = create_form_part("description", _description);
QHttpPart sourcePart = create_form_part("source", "QGroundControl");
QHttpPart versionPart = create_form_part("version", _app->applicationVersion());
QHttpPart logPart;
logPart.setHeader(QNetworkRequest::ContentTypeHeader, "application/octet-stream");
logPart.setHeader(QNetworkRequest::ContentDispositionHeader, QString("form-data; name=\"filearg\"; filename=\"%1\"").arg(fi.fileName()));
logPart.setBodyDevice(file);
QHttpPart sourcePart = create_form_part("source", "QGroundControl");
QHttpPart versionPart = create_form_part("version", _app->applicationVersion());
QHttpPart typePart = create_form_part("type", "flightreport");
QHttpPart windPart = create_form_part("windSpeed", QString::number(_windSpeed));
QHttpPart ratingPart = create_form_part("rating", _rating);
QHttpPart publicPart = create_form_part("public", _publicLog ? "true" : "false");
//-- Assemble request and POST it
multiPart->append(emailPart);
multiPart->append(descriptionPart);
multiPart->append(sourcePart);
multiPart->append(versionPart);
multiPart->append(typePart);
multiPart->append(windPart);
multiPart->append(ratingPart);
multiPart->append(publicPart);
//-- Optional
QHttpPart feedbackPart;
if(_feedback.isEmpty()) {
feedbackPart = create_form_part(kFeedback, "None Given");
} else {
feedbackPart = create_form_part(kFeedback, _feedback);
}
multiPart->append(feedbackPart);
QHttpPart videoPart;
if(_videoURL.isEmpty()) {
videoPart = create_form_part(kVideoURL, "None");
} else {
videoPart = create_form_part(kVideoURL, _videoURL);
}
multiPart->append(videoPart);
//-- Actual Log File
QHttpPart logPart;
logPart.setHeader(QNetworkRequest::ContentTypeHeader, "application/octet-stream");
logPart.setHeader(QNetworkRequest::ContentDispositionHeader, QString("form-data; name=\"filearg\"; filename=\"%1\"").arg(fi.fileName()));
logPart.setBodyDevice(file);
multiPart->append(logPart);
file->setParent(multiPart);
QNetworkRequest request(_uploadURL);
......
......@@ -112,13 +112,18 @@ public:
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 ();
......@@ -129,21 +134,31 @@ public:
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);
......@@ -152,6 +167,7 @@ signals:
void emailAddressChanged ();
void descriptionChanged ();
void uploadURLChanged ();
void feedbackChanged ();
void enableAutoUploadChanged ();
void enableAutoStartChanged ();
void logFilesChanged ();
......@@ -164,6 +180,10 @@ signals:
void logRunningChanged ();
void canStartLogChanged ();
void deleteAfterUploadChanged ();
void windSpeedChanged ();
void ratingChanged ();
void videoURLChanged ();
void publicLogChanged ();
private slots:
void _uploadFinished ();
......@@ -188,7 +208,9 @@ private:
QString _description;
QString _emailAddress;
QString _uploadURL;
QString _feedback;
QString _logPath;
QString _videoURL;
bool _enableAutoUpload;
bool _enableAutoStart;
QNetworkAccessManager* _nam;
......@@ -199,6 +221,9 @@ private:
bool _loggingDisabled;
MAVLinkLogProcessor* _logProcessor;
bool _deleteAfterUpload;
int _windSpeed;
QString _rating;
bool _publicLog;
};
#endif
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment