Unverified Commit 6000c83c authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7536 from DonLakeFlyer/StableMerge

Stable merge
parents ad54ae0a 4b2d7e47
......@@ -33,7 +33,9 @@ Note: This file only contains high level features or important fixes.
* ArduPilot: Support configurable mavlink stream rates. Available from Settings/Mavlink page.
* Major rewrite and bug fix pass through Structure Scan. Previous version had such bad problems that it can no longer be supported. Plans with Structure Scan will need to be recreated. New QGC will not load old Structure Scan plans.
### 3.5.3 - Not yet released
### 3.5.3 - Stable
* Change minimum RTK Survey-In limit to 0.01 meters
* Change Windows driver detection logic
* Fix crash when clicking on GeoFence polygon vertex
* PX4: Fix missing ```MC_YAW_FF``` parameter in PID Tuning
* ArduPilot: Fix parameter file save generating bad characters from git hash
......
......@@ -62,6 +62,7 @@ Section
ReadRegStr $R0 HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${APPNAME}" "UninstallString"
StrCmp $R0 "" doinstall
DetailPrint "Uninstalling previous version..."
ExecWait "$R0 /S _?=$INSTDIR -LEAVE_DATA=1"
IntCmp $0 0 doinstall
......@@ -78,28 +79,25 @@ doinstall:
WriteRegStr HKLM "SOFTWARE\Microsoft\Windows\CurrentVersion\Uninstall\${APPNAME}" "UninstallString" "$\"$INSTDIR\${EXENAME}-Uninstall.exe$\""
SetRegView 64
WriteRegDWORD HKLM "SOFTWARE\Microsoft\Windows\Windows Error Reporting\LocalDumps\${EXENAME}.exe" "DumpCount" 5
WriteRegDWORD HKLM "SOFTWARE\Microsoft\Windows\Windows Error Reporting\LocalDumps\${EXENAME}.exe" "DumpType" 2
WriteRegDWORD HKLM "SOFTWARE\Microsoft\Windows\Windows Error Reporting\LocalDumps\${EXENAME}.exe" "DumpType" 1
WriteRegExpandStr HKLM "SOFTWARE\Microsoft\Windows\Windows Error Reporting\LocalDumps\${EXENAME}.exe" "DumpFolder" "%LOCALAPPDATA%\QGCCrashDumps"
; Only attempt to install the PX4 driver if the version isn't present
!define ROOTKEY "SOFTWARE\Microsoft\Windows\CurrentVersion\Uninstall\434608CF2B6E31F0DDBA5C511053F957B55F098E"
!define DRIVERKEY "SOFTWARE\MichaelOborne\driver"
SetRegView 64
ReadRegStr $0 HKLM "${ROOTKEY}" "Publisher"
StrCmp $0 "3D Robotics" found_provider notfound
ReadRegDWORD $0 HKCU "${DRIVERKEY}" "installed"
IntCmp $0 1 found_provider notfound notfound
found_provider:
ReadRegStr $0 HKLM "${ROOTKEY}" "DisplayVersion"
DetailPrint "Checking USB driver version... $0"
StrCmp $0 "04/11/2013 2.0.0.4" skip_driver notfound
DetailPrint "USB Drivers already installed"
goto done
notfound:
DetailPrint "USB Driver not found... installing"
ExecWait '"msiexec" /i "px4driver.msi"'
goto done
skip_driver:
DetailPrint "USB Driver found... skipping install"
done:
SetRegView lastused
SectionEnd
......
......@@ -2,12 +2,12 @@
{
"name": "surveyInAccuracyLimit",
"shortDescription": "Survey in accuracy (U-blox only)",
"longDescription": "The maximum accuracy allowed prior to completing survey in.",
"longDescription": "The minimum accuracy value that Survey-In must achieve before it can complete.",
"type": "double",
"defaultValue": 2.0,
"min": 0.5,
"min": 0.01,
"units": "m",
"decimalPlaces": 1,
"decimalPlaces": 2,
"qgcRebootRequired": true
},
{
......
......@@ -216,7 +216,9 @@ quint64 LogReplayLink::_seekToNextMavlinkMessage(mavlink_message_t* nextMsg)
mavlink_status_t status;
qint64 messageStartPos = -1;
while (_logFile.getChar(&nextByte)) { // Loop over every byte
mavlink_reset_channel_status(_mavlinkChannel);
while (_logFile.getChar(&nextByte)) {
bool messageFound = mavlink_parse_char(_mavlinkChannel, nextByte, nextMsg, &status);
if (status.parse_state == MAVLINK_PARSE_STATE_GOT_STX) {
......@@ -236,6 +238,31 @@ quint64 LogReplayLink::_seekToNextMavlinkMessage(mavlink_message_t* nextMsg)
return 0;
}
quint64 LogReplayLink::_findLastTimestamp(void)
{
char nextByte;
mavlink_status_t status;
quint64 lastTimestamp = 0;
mavlink_message_t msg;
// We read through the entire file looking for the last good timestamp. This can be somewhat slow, but trying to work from the
// end of the file can be way slower due to all the seeking back and forth required. So instead we take the simple reliable approach.
_logFile.reset();
mavlink_reset_channel_status(_mavlinkChannel);
while (_logFile.bytesAvailable() > cbTimestamp) {
lastTimestamp = _parseTimestamp(_logFile.read(cbTimestamp));
bool endOfMessage = false;
while (!endOfMessage && _logFile.getChar(&nextByte)) {
endOfMessage = mavlink_parse_char(_mavlinkChannel, nextByte, &msg, &status);
}
}
return lastTimestamp;
}
bool LogReplayLink::_loadLogFile(void)
{
QString errorMsg;
......@@ -259,28 +286,11 @@ bool LogReplayLink::_loadLogFile(void)
_logTimestamped = logFilename.endsWith(".tlog");
if (_logTimestamped) {
// Get the first timestamp from the log
// This should be a big-endian uint64.
QByteArray timestamp = _logFile.read(cbTimestamp);
quint64 startTimeUSecs = _parseTimestamp(timestamp);
// Now find the last timestamp by scanning for the last MAVLink packet and
// find the timestamp before it. To do this we start searchin a little before
// the end of the file, specifically the maximum MAVLink packet size + the
// timestamp size. This guarantees that we will hit a MAVLink packet before
// the end of the file. Unfortunately, it basically guarantees that we will
// hit more than one. This is why we have to search for a bit.
qint64 fileLoc = _logFile.size() - ((MAVLINK_MAX_PACKET_LEN - cbTimestamp) * 2);
_logFile.seek(fileLoc);
quint64 endTimeUSecs = startTimeUSecs; // Set a sane default for the endtime
mavlink_message_t msg;
quint64 messageTimeUSecs;
while ((messageTimeUSecs = _seekToNextMavlinkMessage(&msg)) > endTimeUSecs) {
endTimeUSecs = messageTimeUSecs;
}
if (endTimeUSecs == startTimeUSecs) {
errorMsg = tr("The log file '%1' is corrupt. No valid timestamps were found at the end of the file.").arg(logFilename);
quint64 startTimeUSecs = _parseTimestamp(_logFile.read(cbTimestamp));
quint64 endTimeUSecs = _findLastTimestamp();
if (endTimeUSecs <= startTimeUSecs) {
errorMsg = tr("The log file '%1' is corrupt or empty.").arg(logFilename);
goto Error;
}
......
......@@ -112,6 +112,7 @@ private:
void _replayError(const QString& errorMsg);
quint64 _parseTimestamp(const QByteArray& bytes);
quint64 _seekToNextMavlinkMessage(mavlink_message_t* nextMsg);
quint64 _findLastTimestamp(void);
quint64 _readNextMavlinkMessage(QByteArray& bytes);
bool _loadLogFile(void);
void _finishPlayback(void);
......@@ -128,7 +129,7 @@ private:
LogReplayLinkConfiguration* _logReplayConfig;
bool _connected;
int _mavlinkChannel;
uint8_t _mavlinkChannel;
QTimer _readTickTimer; ///< Timer which signals a read of next log record
QString _errorTitle; ///< Title for communicatorError signals
......
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