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
651f110b
Commit
651f110b
authored
Dec 23, 2017
by
Gus Grubba
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'master' of
https://github.com/mavlink/qgroundcontrol
into customMobileFileDlg
parents
8343b39a
66e0e71d
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
60 additions
and
12 deletions
+60
-12
QGCInstaller.pri
QGCInstaller.pri
+3
-2
FactMetaData.cc
src/FactSystem/FactMetaData.cc
+16
-2
FactMetaData.h
src/FactSystem/FactMetaData.h
+2
-0
RTCMMavlink.cc
src/GPS/RTCM/RTCMMavlink.cc
+3
-6
RTCMMavlink.h
src/GPS/RTCM/RTCMMavlink.h
+1
-0
UnitsSettings.cc
src/Settings/UnitsSettings.cc
+23
-0
UnitsSettings.h
src/Settings/UnitsSettings.h
+10
-0
GeneralSettings.qml
src/ui/preferences/GeneralSettings.qml
+2
-2
No files found.
QGCInstaller.pri
View file @
651f110b
...
...
@@ -31,8 +31,9 @@ installer {
# macdeploy is missing some relocations once in a while. "Fix" it:
QMAKE_POST_LINK += && python $$BASEDIR/tools/osxrelocator.py $${TARGET}.app/Contents @rpath @executable_path/../Frameworks -r > /dev/null 2>&1
# Create package
QMAKE_POST_LINK += && cd $${OUT_PWD}
QMAKE_POST_LINK += && hdiutil create -verbose -stretch 4g -layout SPUD -srcfolder $${DESTDIR}/$${TARGET}.app -volname $${TARGET} $${DESTDIR}/package/$${TARGET}.dmg
QMAKE_POST_LINK += && hdiutil create /tmp/tmp.dmg -ov -volname "$${TARGET}-$${MAC_VERSION}" -fs HFS+ -srcfolder "$${DESTDIR}/"
QMAKE_POST_LINK += && hdiutil convert /tmp/tmp.dmg -format UDBZ -o $${DESTDIR}/package/$${TARGET}.dmg
QMAKE_POST_LINK += && rm /tmp/tmp.dmg
}
WindowsBuild {
QMAKE_POST_LINK += $$escape_expand(\\n) cd $$BASEDIR_WIN && $$quote("\"C:\\Program Files \(x86\)\\NSIS\\makensis.exe\"" /DINSTALLER_ICON="\"$${QGC_INSTALLER_ICON}\"" /DHEADER_BITMAP="\"$${QGC_INSTALLER_HEADER_BITMAP}\"" /DAPPNAME="\"$${QGC_APP_NAME}\"" /DEXENAME="\"$${TARGET}\"" /DORGNAME="\"$${QGC_ORG_NAME}\"" /DDESTDIR=$${DESTDIR} /NOCD "\"/XOutFile $${DESTDIR_WIN}\\$${TARGET}-installer.exe\"" "$$BASEDIR_WIN\\deploy\\qgroundcontrol_installer.nsi")
...
...
src/FactSystem/FactMetaData.cc
View file @
651f110b
...
...
@@ -46,6 +46,7 @@ const FactMetaData::AppSettingsTranslation_s FactMetaData::_rgAppSettingsTransla
{
"meters"
,
"meters"
,
false
,
UnitsSettings
::
DistanceUnitsMeters
,
FactMetaData
::
_defaultTranslator
,
FactMetaData
::
_defaultTranslator
},
{
"cm/px"
,
"cm/px"
,
false
,
UnitsSettings
::
DistanceUnitsMeters
,
FactMetaData
::
_defaultTranslator
,
FactMetaData
::
_defaultTranslator
},
{
"m/s"
,
"m/s"
,
true
,
UnitsSettings
::
SpeedUnitsMetersPerSecond
,
FactMetaData
::
_defaultTranslator
,
FactMetaData
::
_defaultTranslator
},
{
"C"
,
"C"
,
false
,
UnitsSettings
::
TemperatureUnitsCelsius
,
FactMetaData
::
_defaultTranslator
,
FactMetaData
::
_defaultTranslator
},
{
"m^2"
,
"m^2"
,
false
,
UnitsSettings
::
AreaUnitsSquareMeters
,
FactMetaData
::
_defaultTranslator
,
FactMetaData
::
_defaultTranslator
},
{
"m"
,
"ft"
,
false
,
UnitsSettings
::
DistanceUnitsFeet
,
FactMetaData
::
_metersToFeet
,
FactMetaData
::
_feetToMeters
},
{
"meters"
,
"ft"
,
false
,
UnitsSettings
::
DistanceUnitsFeet
,
FactMetaData
::
_metersToFeet
,
FactMetaData
::
_feetToMeters
},
...
...
@@ -59,6 +60,7 @@ const FactMetaData::AppSettingsTranslation_s FactMetaData::_rgAppSettingsTransla
{
"m/s"
,
"mph"
,
true
,
UnitsSettings
::
SpeedUnitsMilesPerHour
,
FactMetaData
::
_metersPerSecondToMilesPerHour
,
FactMetaData
::
_milesPerHourToMetersPerSecond
},
{
"m/s"
,
"km/h"
,
true
,
UnitsSettings
::
SpeedUnitsKilometersPerHour
,
FactMetaData
::
_metersPerSecondToKilometersPerHour
,
FactMetaData
::
_kilometersPerHourToMetersPerSecond
},
{
"m/s"
,
"kn"
,
true
,
UnitsSettings
::
SpeedUnitsKnots
,
FactMetaData
::
_metersPerSecondToKnots
,
FactMetaData
::
_knotsToMetersPerSecond
},
{
"C"
,
"F"
,
false
,
UnitsSettings
::
TemperatureUnitsFarenheit
,
FactMetaData
::
_celsiusToFarenheit
,
FactMetaData
::
_farenheitToCelsius
},
};
const
char
*
FactMetaData
::
_decimalPlacesJsonKey
=
"decimalPlaces"
;
...
...
@@ -685,6 +687,16 @@ QVariant FactMetaData::_inchesToCentimeters(const QVariant& inches)
return
QVariant
(
inches
.
toDouble
()
*
constants
.
inchesToCentimeters
);
}
QVariant
FactMetaData
::
_celsiusToFarenheit
(
const
QVariant
&
celsius
)
{
return
QVariant
(
celsius
.
toDouble
()
*
(
9.0
/
5.0
)
+
32
);
}
QVariant
FactMetaData
::
_farenheitToCelsius
(
const
QVariant
&
farenheit
)
{
return
QVariant
((
farenheit
.
toDouble
()
-
32
)
*
(
5.0
/
9.0
));
}
void
FactMetaData
::
setRawUnits
(
const
QString
&
rawUnits
)
{
_rawUnits
=
rawUnits
;
...
...
@@ -774,9 +786,11 @@ void FactMetaData::_setAppSettingsTranslators(void)
for
(
size_t
i
=
0
;
i
<
sizeof
(
_rgAppSettingsTranslations
)
/
sizeof
(
_rgAppSettingsTranslations
[
0
]);
i
++
)
{
const
AppSettingsTranslation_s
*
pAppSettingsTranslation
=
&
_rgAppSettingsTranslations
[
i
];
if
(
pAppSettingsTranslation
->
rawUnits
==
_rawUnits
.
toLower
()
&&
if
((
pAppSettingsTranslation
->
rawUnits
==
_rawUnits
&&
// Temperature
(
!
pAppSettingsTranslation
->
speed
&&
pAppSettingsTranslation
->
speedOrDistanceUnits
==
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
unitsSettings
()
->
temperatureUnits
()
->
rawValue
().
toUInt
()))
||
(
pAppSettingsTranslation
->
rawUnits
==
_rawUnits
.
toLower
()
&&
// Speed and Distance
((
pAppSettingsTranslation
->
speed
&&
pAppSettingsTranslation
->
speedOrDistanceUnits
==
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
unitsSettings
()
->
speedUnits
()
->
rawValue
().
toUInt
())
||
(
!
pAppSettingsTranslation
->
speed
&&
pAppSettingsTranslation
->
speedOrDistanceUnits
==
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
unitsSettings
()
->
distanceUnits
()
->
rawValue
().
toUInt
(
))))
{
(
!
pAppSettingsTranslation
->
speed
&&
pAppSettingsTranslation
->
speedOrDistanceUnits
==
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
unitsSettings
()
->
distanceUnits
()
->
rawValue
().
toUInt
()
))))
{
_cookedUnits
=
pAppSettingsTranslation
->
cookedUnits
;
setTranslators
(
pAppSettingsTranslation
->
rawTranslator
,
pAppSettingsTranslation
->
cookedTranslator
);
return
;
...
...
src/FactSystem/FactMetaData.h
View file @
651f110b
...
...
@@ -193,6 +193,8 @@ private:
static
QVariant
_normToPercent
(
const
QVariant
&
normalized
);
static
QVariant
_centimetersToInches
(
const
QVariant
&
centimeters
);
static
QVariant
_inchesToCentimeters
(
const
QVariant
&
inches
);
static
QVariant
_celsiusToFarenheit
(
const
QVariant
&
celsius
);
static
QVariant
_farenheitToCelsius
(
const
QVariant
&
farenheit
);
struct
AppSettingsTranslation_s
{
const
char
*
rawUnits
;
...
...
src/GPS/RTCM/RTCMMavlink.cc
View file @
651f110b
...
...
@@ -38,29 +38,26 @@ void RTCMMavlink::RTCMDataUpdate(QByteArray message)
if
(
message
.
size
()
<
maxMessageLength
)
{
mavlinkRtcmData
.
len
=
message
.
size
();
mavlinkRtcmData
.
flags
=
(
_sequenceId
&
0x1F
)
<<
3
;
memcpy
(
&
mavlinkRtcmData
.
data
,
message
.
data
(),
message
.
size
());
sendMessageToVehicle
(
mavlinkRtcmData
);
}
else
{
// We need to fragment
static
uint8_t
sequenceId
=
0
;
// Sequence id is used to indicate that the individual fragements belong to the same set
uint8_t
fragmentId
=
0
;
// Fragment id indicates the fragment within a set
int
start
=
0
;
while
(
start
<
message
.
size
())
{
int
length
=
std
::
min
(
message
.
size
()
-
start
,
maxMessageLength
);
mavlinkRtcmData
.
flags
=
1
;
// LSB set indicates message is fragmented
mavlinkRtcmData
.
flags
|=
fragmentId
++
<<
1
;
// Next 2 bits are fragment id
mavlinkRtcmData
.
flags
|=
sequenceId
++
<<
3
;
// Next 5 bits are sequence id
mavlinkRtcmData
.
flags
|=
(
_sequenceId
&
0x1F
)
<<
3
;
// Next 5 bits are sequence id
mavlinkRtcmData
.
len
=
length
;
memcpy
(
&
mavlinkRtcmData
.
data
,
message
.
data
()
+
start
,
length
);
sendMessageToVehicle
(
mavlinkRtcmData
);
start
+=
length
;
}
if
(
sequenceId
==
0x1F
)
{
sequenceId
=
0
;
}
}
++
_sequenceId
;
}
void
RTCMMavlink
::
sendMessageToVehicle
(
const
mavlink_gps_rtcm_data_t
&
msg
)
...
...
src/GPS/RTCM/RTCMMavlink.h
View file @
651f110b
...
...
@@ -36,4 +36,5 @@ private:
QGCToolbox
&
_toolbox
;
QElapsedTimer
_bandwidthTimer
;
int
_bandwidthByteCounter
=
0
;
uint8_t
_sequenceId
=
0
;
};
src/Settings/UnitsSettings.cc
View file @
651f110b
...
...
@@ -16,12 +16,14 @@ const char* UnitsSettings::unitsSettingsGroupName = "Units";
const
char
*
UnitsSettings
::
distanceUnitsSettingsName
=
"DistanceUnits"
;
const
char
*
UnitsSettings
::
areaUnitsSettingsName
=
"AreaUnits"
;
const
char
*
UnitsSettings
::
speedUnitsSettingsName
=
"SpeedUnits"
;
const
char
*
UnitsSettings
::
temperatureUnitsSettingsName
=
"TemperatureUnits"
;
UnitsSettings
::
UnitsSettings
(
QObject
*
parent
)
:
SettingsGroup
(
unitsSettingsGroupName
,
QString
()
/* root settings group */
,
parent
)
,
_distanceUnitsFact
(
NULL
)
,
_areaUnitsFact
(
NULL
)
,
_speedUnitsFact
(
NULL
)
,
_temperatureUnitsFact
(
NULL
)
{
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
qmlRegisterUncreatableType
<
UnitsSettings
>
(
"QGroundControl.SettingsManager"
,
1
,
0
,
"UnitsSettings"
,
"Reference only"
);
...
...
@@ -92,3 +94,24 @@ Fact* UnitsSettings::speedUnits(void)
return
_speedUnitsFact
;
}
Fact
*
UnitsSettings
::
temperatureUnits
(
void
)
{
if
(
!
_temperatureUnitsFact
)
{
// Units settings can't be loaded from json since it creates an infinite loop of meta data loading.
QStringList
enumStrings
;
QVariantList
enumValues
;
enumStrings
<<
"Celsius"
<<
"Farenheit"
;
enumValues
<<
QVariant
::
fromValue
((
uint32_t
)
TemperatureUnitsCelsius
)
<<
QVariant
::
fromValue
((
uint32_t
)
TemperatureUnitsFarenheit
);
FactMetaData
*
metaData
=
new
FactMetaData
(
FactMetaData
::
valueTypeUint32
,
this
);
metaData
->
setName
(
temperatureUnitsSettingsName
);
metaData
->
setEnumInfo
(
enumStrings
,
enumValues
);
metaData
->
setRawDefaultValue
(
TemperatureUnitsCelsius
);
_temperatureUnitsFact
=
new
SettingsFact
(
QString
()
/* no settings group */
,
metaData
,
this
);
}
return
_temperatureUnitsFact
;
}
src/Settings/UnitsSettings.h
View file @
651f110b
...
...
@@ -41,28 +41,38 @@ public:
SpeedUnitsKnots
,
};
enum
TemperatureUnits
{
TemperatureUnitsCelsius
=
0
,
TemperatureUnitsFarenheit
,
};
Q_ENUMS
(
DistanceUnits
)
Q_ENUMS
(
AreaUnits
)
Q_ENUMS
(
SpeedUnits
)
Q_ENUMS
(
TemperatureUnits
)
Q_PROPERTY
(
Fact
*
distanceUnits
READ
distanceUnits
CONSTANT
)
Q_PROPERTY
(
Fact
*
areaUnits
READ
areaUnits
CONSTANT
)
Q_PROPERTY
(
Fact
*
speedUnits
READ
speedUnits
CONSTANT
)
Q_PROPERTY
(
Fact
*
temperatureUnits
READ
temperatureUnits
CONSTANT
)
Fact
*
distanceUnits
(
void
);
Fact
*
areaUnits
(
void
);
Fact
*
speedUnits
(
void
);
Fact
*
temperatureUnits
(
void
);
static
const
char
*
unitsSettingsGroupName
;
static
const
char
*
distanceUnitsSettingsName
;
static
const
char
*
areaUnitsSettingsName
;
static
const
char
*
speedUnitsSettingsName
;
static
const
char
*
temperatureUnitsSettingsName
;
private:
SettingsFact
*
_distanceUnitsFact
;
SettingsFact
*
_areaUnitsFact
;
SettingsFact
*
_speedUnitsFact
;
SettingsFact
*
_temperatureUnitsFact
;
};
#endif
src/ui/preferences/GeneralSettings.qml
View file @
651f110b
...
...
@@ -88,9 +88,9 @@ QGCView {
Repeater
{
id
:
unitsRepeater
model
:
[
QGroundControl
.
settingsManager
.
unitsSettings
.
distanceUnits
,
QGroundControl
.
settingsManager
.
unitsSettings
.
areaUnits
,
QGroundControl
.
settingsManager
.
unitsSettings
.
speedUnits
]
model
:
[
QGroundControl
.
settingsManager
.
unitsSettings
.
distanceUnits
,
QGroundControl
.
settingsManager
.
unitsSettings
.
areaUnits
,
QGroundControl
.
settingsManager
.
unitsSettings
.
speedUnits
,
QGroundControl
.
settingsManager
.
unitsSettings
.
temperatureUnits
]
property
var
names
:
[
qsTr
(
"
Distance:
"
),
qsTr
(
"
Area:
"
),
qsTr
(
"
Speed:
"
)
]
property
var
names
:
[
qsTr
(
"
Distance:
"
),
qsTr
(
"
Area:
"
),
qsTr
(
"
Speed:
"
)
,
qsTr
(
"
Temperature:
"
)
]
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
...
...
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