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
158fd4e5
Commit
158fd4e5
authored
Oct 08, 2018
by
Willian Galvani
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
FirmwarePlugin.cc: update to use versionCompare()
parent
0b5fb0dc
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
26 additions
and
68 deletions
+26
-68
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+23
-52
FirmwarePlugin.cc
src/FirmwarePlugin/FirmwarePlugin.cc
+3
-16
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
158fd4e5
...
...
@@ -761,9 +761,6 @@ void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketErr
QString
APMFirmwarePlugin
::
internalParameterMetaDataFile
(
Vehicle
*
vehicle
)
{
int
majorVersion
=
vehicle
->
firmwareMajorVersion
();
int
minorVersion
=
vehicle
->
firmwareMinorVersion
();
switch
(
vehicle
->
vehicleType
())
{
case
MAV_TYPE_QUADROTOR
:
case
MAV_TYPE_HEXAROTOR
:
...
...
@@ -771,25 +768,17 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case
MAV_TYPE_TRICOPTER
:
case
MAV_TYPE_COAXIAL
:
case
MAV_TYPE_HELICOPTER
:
if
(
majorVersion
<
3
)
{
if
(
vehicle
->
versionCompare
(
3
,
4
,
0
)
<
0
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"
);
}
else
if
(
majorVersion
==
3
)
{
switch
(
minorVersion
)
{
case
0
:
case
1
:
case
2
:
case
3
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"
);
case
4
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml"
);
case
5
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"
);
case
6
:
default:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml"
);
}
}
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"
);
if
(
vehicle
->
versionCompare
(
3
,
5
,
0
)
<
0
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml"
);
}
if
(
vehicle
->
versionCompare
(
3
,
6
,
0
)
<
0
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"
);
}
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml"
);
case
MAV_TYPE_VTOL_DUOROTOR
:
case
MAV_TYPE_VTOL_QUADROTOR
:
case
MAV_TYPE_VTOL_TILTROTOR
:
...
...
@@ -798,45 +787,27 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case
MAV_TYPE_VTOL_RESERVED4
:
case
MAV_TYPE_VTOL_RESERVED5
:
case
MAV_TYPE_FIXED_WING
:
if
(
majorVersion
<
3
)
{
if
(
vehicle
->
versionCompare
(
3
,
5
,
0
)
<
0
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"
);
}
else
if
(
majorVersion
==
3
)
{
switch
(
minorVersion
)
{
case
0
:
case
1
:
case
2
:
case
3
:
case
4
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"
);
case
5
:
case
6
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml"
);
case
7
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.7.xml"
);
case
8
:
default:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml"
);
}
}
if
(
vehicle
->
versionCompare
(
3
,
7
,
0
)
<
0
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml"
);
}
if
(
vehicle
->
versionCompare
(
3
,
8
,
0
)
<
0
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.7.xml"
);
}
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml"
);
case
MAV_TYPE_GROUND_ROVER
:
case
MAV_TYPE_SURFACE_BOAT
:
if
(
majorVersion
<
3
)
{
if
(
vehicle
->
versionCompare
(
3
,
2
,
0
)
<
0
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"
);
}
else
if
(
majorVersion
==
3
)
{
switch
(
minorVersion
)
{
case
0
:
case
1
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"
);
case
2
:
case
3
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"
);
case
4
:
default:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.4.xml"
);
}
}
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"
);
if
(
vehicle
->
versionCompare
(
3
,
4
,
0
)
<
0
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"
);
}
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.4.xml"
);
case
MAV_TYPE_SUBMARINE
:
if
(
vehicle
->
firmwareMajorVersion
()
<
3
||
(
vehicle
->
firmwareMajorVersion
()
==
3
&&
vehicle
->
firmwareMinorVersion
()
<=
4
))
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml"
);
...
...
src/FirmwarePlugin/FirmwarePlugin.cc
View file @
158fd4e5
...
...
@@ -713,25 +713,12 @@ void FirmwarePlugin::_versionFileDownloadFinished(QString& remoteFile, QString&
}
qCDebug
(
FirmwarePluginLog
)
<<
"Latest stable version = "
<<
version
;
QStringList
versionNumbers
=
version
.
split
(
"."
);
if
(
versionNumbers
.
size
()
!=
3
)
{
qCWarning
(
FirmwarePluginLog
)
<<
"Error parsing version number: wrong format"
;
return
;
}
int
stableMajor
=
versionNumbers
[
0
].
toInt
();
int
stableMinor
=
versionNumbers
[
1
].
toInt
();
int
stablePatch
=
versionNumbers
[
2
].
toInt
();
int
currMajor
=
vehicle
->
firmwareMajorVersion
();
int
currMinor
=
vehicle
->
firmwareMinorVersion
();
int
currPatch
=
vehicle
->
firmwarePatchVersion
();
int
currType
=
vehicle
->
firmwareVersionType
();
if
(
currMajor
<
stableMajor
||
(
currMajor
==
stableMajor
&&
currMinor
<
stableMinor
)
||
(
currMajor
==
stableMajor
&&
currMinor
==
stableMinor
&&
currPatch
<
stablePatch
)
||
(
currMajor
==
stableMajor
&&
currMinor
==
stableMinor
&&
currPatch
==
stablePatch
&&
currType
!=
FIRMWARE_VERSION_TYPE_OFFICIAL
)
)
// Check if lower version than stable or same version but different type
if
(
vehicle
->
versionCompare
(
version
)
<
0
||
(
vehicle
->
versionCompare
(
version
)
==
0
&&
currType
!=
FIRMWARE_VERSION_TYPE_OFFICIAL
))
{
const
static
QString
currentVersion
=
QString
(
"%1.%2.%3"
).
arg
(
vehicle
->
firmwareMajorVersion
())
.
arg
(
vehicle
->
firmwareMinorVersion
())
...
...
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