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
182f6b1a
Commit
182f6b1a
authored
Jul 25, 2016
by
Don Gagne
Committed by
GitHub
Jul 25, 2016
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #3828 from birchera/area_translations
[Mission stats] Added area translation
parents
f7a9f4e5
af661737
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
189 additions
and
0 deletions
+189
-0
FactMetaData.cc
src/FactSystem/FactMetaData.cc
+101
-0
FactMetaData.h
src/FactSystem/FactMetaData.h
+20
-0
QGroundControlQmlGlobal.cc
src/QmlControls/QGroundControlQmlGlobal.cc
+22
-0
QGroundControlQmlGlobal.h
src/QmlControls/QGroundControlQmlGlobal.h
+23
-0
GeneralSettings.qml
src/ui/preferences/GeneralSettings.qml
+23
-0
No files found.
src/FactSystem/FactMetaData.cc
View file @
182f6b1a
...
...
@@ -45,8 +45,14 @@ const FactMetaData::AppSettingsTranslation_s FactMetaData::_rgAppSettingsTransla
{
"m"
,
"m"
,
false
,
QGroundControlQmlGlobal
::
DistanceUnitsMeters
,
FactMetaData
::
_defaultTranslator
,
FactMetaData
::
_defaultTranslator
},
{
"meters"
,
"meters"
,
false
,
QGroundControlQmlGlobal
::
DistanceUnitsMeters
,
FactMetaData
::
_defaultTranslator
,
FactMetaData
::
_defaultTranslator
},
{
"m/s"
,
"m/s"
,
true
,
QGroundControlQmlGlobal
::
SpeedUnitsMetersPerSecond
,
FactMetaData
::
_defaultTranslator
,
FactMetaData
::
_defaultTranslator
},
{
"m^2"
,
"m^2"
,
false
,
QGroundControlQmlGlobal
::
AreaUnitsSquareMeters
,
FactMetaData
::
_defaultTranslator
,
FactMetaData
::
_defaultTranslator
},
{
"m"
,
"ft"
,
false
,
QGroundControlQmlGlobal
::
DistanceUnitsFeet
,
FactMetaData
::
_metersToFeet
,
FactMetaData
::
_feetToMeters
},
{
"meters"
,
"ft"
,
false
,
QGroundControlQmlGlobal
::
DistanceUnitsFeet
,
FactMetaData
::
_metersToFeet
,
FactMetaData
::
_feetToMeters
},
{
"m^2"
,
"km^2"
,
false
,
QGroundControlQmlGlobal
::
AreaUnitsSquareKilometers
,
FactMetaData
::
_squareMetersToSquareKilometers
,
FactMetaData
::
_squareKilometersToSquareMeters
},
{
"m^2"
,
"ha"
,
false
,
QGroundControlQmlGlobal
::
AreaUnitsHectares
,
FactMetaData
::
_squareMetersToHectares
,
FactMetaData
::
_hectaresToSquareMeters
},
{
"m^2"
,
"ft^2"
,
false
,
QGroundControlQmlGlobal
::
AreaUnitsSquareFeet
,
FactMetaData
::
_squareMetersToSquareFeet
,
FactMetaData
::
_squareFeetToSquareMeters
},
{
"m^2"
,
"ac"
,
false
,
QGroundControlQmlGlobal
::
AreaUnitsAcres
,
FactMetaData
::
_squareMetersToAcres
,
FactMetaData
::
_acresToSquareMeters
},
{
"m^2"
,
"mi^2"
,
false
,
QGroundControlQmlGlobal
::
AreaUnitsSquareMiles
,
FactMetaData
::
_squareMetersToSquareMiles
,
FactMetaData
::
_squareMilesToSquareMeters
},
{
"m/s"
,
"ft/s"
,
true
,
QGroundControlQmlGlobal
::
SpeedUnitsFeetPerSecond
,
FactMetaData
::
_metersToFeet
,
FactMetaData
::
_feetToMeters
},
{
"m/s"
,
"mph"
,
true
,
QGroundControlQmlGlobal
::
SpeedUnitsMilesPerHour
,
FactMetaData
::
_metersPerSecondToMilesPerHour
,
FactMetaData
::
_milesPerHourToMetersPerSecond
},
{
"m/s"
,
"km/h"
,
true
,
QGroundControlQmlGlobal
::
SpeedUnitsKilometersPerHour
,
FactMetaData
::
_metersPerSecondToKilometersPerHour
,
FactMetaData
::
_kilometersPerHourToMetersPerSecond
},
...
...
@@ -419,6 +425,56 @@ QVariant FactMetaData::_feetToMeters(const QVariant& feet)
return
QVariant
(
feet
.
toDouble
()
*
constants
.
feetToMeters
);
}
QVariant
FactMetaData
::
_squareMetersToSquareKilometers
(
const
QVariant
&
squareMeters
)
{
return
QVariant
(
squareMeters
.
toDouble
()
*
0.000001
);
}
QVariant
FactMetaData
::
_squareKilometersToSquareMeters
(
const
QVariant
&
squareKilometers
)
{
return
QVariant
(
squareKilometers
.
toDouble
()
*
1000000.0
);
}
QVariant
FactMetaData
::
_squareMetersToHectares
(
const
QVariant
&
squareMeters
)
{
return
QVariant
(
squareMeters
.
toDouble
()
*
0.0001
);
}
QVariant
FactMetaData
::
_hectaresToSquareMeters
(
const
QVariant
&
hectares
)
{
return
QVariant
(
hectares
.
toDouble
()
*
1000.0
);
}
QVariant
FactMetaData
::
_squareMetersToSquareFeet
(
const
QVariant
&
squareMeters
)
{
return
QVariant
(
squareMeters
.
toDouble
()
*
10.7639
);
}
QVariant
FactMetaData
::
_squareFeetToSquareMeters
(
const
QVariant
&
squareFeet
)
{
return
QVariant
(
squareFeet
.
toDouble
()
*
0.0929
);
}
QVariant
FactMetaData
::
_squareMetersToAcres
(
const
QVariant
&
squareMeters
)
{
return
QVariant
(
squareMeters
.
toDouble
()
*
0.000247105
);
}
QVariant
FactMetaData
::
_acresToSquareMeters
(
const
QVariant
&
acres
)
{
return
QVariant
(
acres
.
toDouble
()
*
4046.86
);
}
QVariant
FactMetaData
::
_squareMetersToSquareMiles
(
const
QVariant
&
squareMeters
)
{
return
QVariant
(
squareMeters
.
toDouble
()
*
3.86102e-7
);
}
QVariant
FactMetaData
::
_squareMilesToSquareMeters
(
const
QVariant
&
squareMiles
)
{
return
QVariant
(
squareMiles
.
toDouble
()
*
258999039.98855
);
}
QVariant
FactMetaData
::
_metersPerSecondToMilesPerHour
(
const
QVariant
&
metersPerSecond
)
{
return
QVariant
((
metersPerSecond
.
toDouble
()
*
1.0
/
constants
.
milesToMeters
)
*
constants
.
secondsPerHour
);
...
...
@@ -559,6 +615,21 @@ const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsDist
return
NULL
;
}
const
FactMetaData
::
AppSettingsTranslation_s
*
FactMetaData
::
_findAppSettingsAreaUnitsTranslation
(
const
QString
&
rawUnits
)
{
for
(
size_t
i
=
0
;
i
<
sizeof
(
_rgAppSettingsTranslations
)
/
sizeof
(
_rgAppSettingsTranslations
[
0
]);
i
++
)
{
const
AppSettingsTranslation_s
*
pAppSettingsTranslation
=
&
_rgAppSettingsTranslations
[
i
];
if
(
pAppSettingsTranslation
->
rawUnits
==
rawUnits
&&
(
!
pAppSettingsTranslation
->
speed
&&
pAppSettingsTranslation
->
speedOrDistanceUnits
==
QGroundControlQmlGlobal
::
areaUnits
()
->
rawValue
().
toUInt
())
)
{
return
pAppSettingsTranslation
;
}
}
return
NULL
;
}
QVariant
FactMetaData
::
metersToAppSettingsDistanceUnits
(
const
QVariant
&
meters
)
{
const
AppSettingsTranslation_s
*
pAppSettingsTranslation
=
_findAppSettingsDistanceUnitsTranslation
(
"m"
);
...
...
@@ -589,6 +660,36 @@ QString FactMetaData::appSettingsDistanceUnitsString(void)
}
}
QVariant
FactMetaData
::
squareMetersToAppSettingsAreaUnits
(
const
QVariant
&
squareMeters
)
{
const
AppSettingsTranslation_s
*
pAppSettingsTranslation
=
_findAppSettingsAreaUnitsTranslation
(
"m^2"
);
if
(
pAppSettingsTranslation
)
{
return
pAppSettingsTranslation
->
rawTranslator
(
squareMeters
);
}
else
{
return
squareMeters
;
}
}
QVariant
FactMetaData
::
appSettingsAreaUnitsToSquareMeters
(
const
QVariant
&
area
)
{
const
AppSettingsTranslation_s
*
pAppSettingsTranslation
=
_findAppSettingsAreaUnitsTranslation
(
"m^2"
);
if
(
pAppSettingsTranslation
)
{
return
pAppSettingsTranslation
->
cookedTranslator
(
area
);
}
else
{
return
area
;
}
}
QString
FactMetaData
::
appSettingsAreaUnitsString
(
void
)
{
const
AppSettingsTranslation_s
*
pAppSettingsTranslation
=
_findAppSettingsAreaUnitsTranslation
(
"m^2"
);
if
(
pAppSettingsTranslation
)
{
return
pAppSettingsTranslation
->
cookedUnits
;
}
else
{
return
QStringLiteral
(
"m^2"
);
}
}
int
FactMetaData
::
decimalPlaces
(
void
)
const
{
int
actualDecimalPlaces
=
defaultDecimalPlaces
;
...
...
src/FactSystem/FactMetaData.h
View file @
182f6b1a
...
...
@@ -57,6 +57,15 @@ public:
/// Returns the string for distance units which has configued by user
static
QString
appSettingsDistanceUnitsString
(
void
);
/// Converts from meters to the user specified distance unit
static
QVariant
squareMetersToAppSettingsAreaUnits
(
const
QVariant
&
squareMeters
);
/// Converts from user specified distance unit to meters
static
QVariant
appSettingsAreaUnitsToSquareMeters
(
const
QVariant
&
area
);
/// Returns the string for distance units which has configued by user
static
QString
appSettingsAreaUnitsString
(
void
);
int
decimalPlaces
(
void
)
const
;
QVariant
rawDefaultValue
(
void
)
const
;
QVariant
cookedDefaultValue
(
void
)
const
{
return
_rawTranslator
(
rawDefaultValue
());
}
...
...
@@ -144,6 +153,16 @@ private:
static
QVariant
_degreesToCentiDegrees
(
const
QVariant
&
degrees
);
static
QVariant
_metersToFeet
(
const
QVariant
&
meters
);
static
QVariant
_feetToMeters
(
const
QVariant
&
feet
);
static
QVariant
_squareMetersToSquareKilometers
(
const
QVariant
&
squareMeters
);
static
QVariant
_squareKilometersToSquareMeters
(
const
QVariant
&
squareKilometers
);
static
QVariant
_squareMetersToHectares
(
const
QVariant
&
squareMeters
);
static
QVariant
_hectaresToSquareMeters
(
const
QVariant
&
hectares
);
static
QVariant
_squareMetersToSquareFeet
(
const
QVariant
&
squareMeters
);
static
QVariant
_squareFeetToSquareMeters
(
const
QVariant
&
squareFeet
);
static
QVariant
_squareMetersToAcres
(
const
QVariant
&
squareMeters
);
static
QVariant
_acresToSquareMeters
(
const
QVariant
&
acres
);
static
QVariant
_squareMetersToSquareMiles
(
const
QVariant
&
squareMeters
);
static
QVariant
_squareMilesToSquareMeters
(
const
QVariant
&
squareMiles
);
static
QVariant
_metersPerSecondToMilesPerHour
(
const
QVariant
&
metersPerSecond
);
static
QVariant
_milesPerHourToMetersPerSecond
(
const
QVariant
&
milesPerHour
);
static
QVariant
_metersPerSecondToKilometersPerHour
(
const
QVariant
&
metersPerSecond
);
...
...
@@ -164,6 +183,7 @@ private:
};
static
const
AppSettingsTranslation_s
*
_findAppSettingsDistanceUnitsTranslation
(
const
QString
&
rawUnits
);
static
const
AppSettingsTranslation_s
*
_findAppSettingsAreaUnitsTranslation
(
const
QString
&
rawUnits
);
ValueType_t
_type
;
// must be first for correct constructor init
int
_decimalPlaces
;
...
...
src/QmlControls/QGroundControlQmlGlobal.cc
View file @
182f6b1a
...
...
@@ -23,6 +23,8 @@ SettingsFact* QGroundControlQmlGlobal::_offlineEditingFirmwareTypeFact =
FactMetaData
*
QGroundControlQmlGlobal
::
_offlineEditingFirmwareTypeMetaData
=
NULL
;
SettingsFact
*
QGroundControlQmlGlobal
::
_distanceUnitsFact
=
NULL
;
FactMetaData
*
QGroundControlQmlGlobal
::
_distanceUnitsMetaData
=
NULL
;
SettingsFact
*
QGroundControlQmlGlobal
::
_areaUnitsFact
=
NULL
;
FactMetaData
*
QGroundControlQmlGlobal
::
_areaUnitsMetaData
=
NULL
;
SettingsFact
*
QGroundControlQmlGlobal
::
_speedUnitsFact
=
NULL
;
FactMetaData
*
QGroundControlQmlGlobal
::
_speedUnitsMetaData
=
NULL
;
...
...
@@ -248,6 +250,26 @@ Fact* QGroundControlQmlGlobal::distanceUnits(void)
}
Fact
*
QGroundControlQmlGlobal
::
areaUnits
(
void
)
{
if
(
!
_areaUnitsFact
)
{
QStringList
enumStrings
;
QVariantList
enumValues
;
_areaUnitsFact
=
new
SettingsFact
(
QString
(),
"AreaUnits"
,
FactMetaData
::
valueTypeUint32
,
AreaUnitsSquareMeters
);
_areaUnitsMetaData
=
new
FactMetaData
(
FactMetaData
::
valueTypeUint32
);
enumStrings
<<
"SquareFeet"
<<
"SquareMeters"
<<
"SquareKilometers"
<<
"Hectares"
<<
"Acres"
<<
"SquareMiles"
;
enumValues
<<
QVariant
::
fromValue
((
uint32_t
)
AreaUnitsSquareFeet
)
<<
QVariant
::
fromValue
((
uint32_t
)
AreaUnitsSquareMeters
)
<<
QVariant
::
fromValue
((
uint32_t
)
AreaUnitsSquareKilometers
)
<<
QVariant
::
fromValue
((
uint32_t
)
AreaUnitsHectares
)
<<
QVariant
::
fromValue
((
uint32_t
)
AreaUnitsAcres
)
<<
QVariant
::
fromValue
((
uint32_t
)
AreaUnitsSquareMiles
);
_areaUnitsMetaData
->
setEnumInfo
(
enumStrings
,
enumValues
);
_areaUnitsFact
->
setMetaData
(
_areaUnitsMetaData
);
}
return
_areaUnitsFact
;
}
Fact
*
QGroundControlQmlGlobal
::
speedUnits
(
void
)
{
if
(
!
_speedUnitsFact
)
{
...
...
src/QmlControls/QGroundControlQmlGlobal.h
View file @
182f6b1a
...
...
@@ -44,6 +44,15 @@ public:
DistanceUnitsMeters
};
enum
AreaUnits
{
AreaUnitsSquareFeet
=
0
,
AreaUnitsSquareMeters
,
AreaUnitsSquareKilometers
,
AreaUnitsHectares
,
AreaUnitsAcres
,
AreaUnitsSquareMiles
,
};
enum
SpeedUnits
{
SpeedUnitsFeetPerSecond
=
0
,
SpeedUnitsMetersPerSecond
,
...
...
@@ -53,6 +62,7 @@ public:
};
Q_ENUMS
(
DistanceUnits
)
Q_ENUMS
(
AreaUnits
)
Q_ENUMS
(
SpeedUnits
)
Q_PROPERTY
(
FlightMapSettings
*
flightMapSettings
READ
flightMapSettings
CONSTANT
)
...
...
@@ -83,6 +93,7 @@ public:
Q_PROPERTY
(
Fact
*
offlineEditingFirmwareType
READ
offlineEditingFirmwareType
CONSTANT
)
Q_PROPERTY
(
Fact
*
distanceUnits
READ
distanceUnits
CONSTANT
)
Q_PROPERTY
(
Fact
*
areaUnits
READ
areaUnits
CONSTANT
)
Q_PROPERTY
(
Fact
*
speedUnits
READ
speedUnits
CONSTANT
)
Q_PROPERTY
(
QGeoCoordinate
lastKnownHomePosition
READ
lastKnownHomePosition
CONSTANT
)
...
...
@@ -95,6 +106,7 @@ public:
/// Returns the string for distance units which has configued by user
Q_PROPERTY
(
QString
appSettingsDistanceUnitsString
READ
appSettingsDistanceUnitsString
CONSTANT
)
Q_PROPERTY
(
QString
appSettingsAreaUnitsString
READ
appSettingsAreaUnitsString
CONSTANT
)
Q_INVOKABLE
void
saveGlobalSetting
(
const
QString
&
key
,
const
QString
&
value
);
Q_INVOKABLE
QString
loadGlobalSetting
(
const
QString
&
key
,
const
QString
&
defaultValue
);
...
...
@@ -118,6 +130,14 @@ public:
QString
appSettingsDistanceUnitsString
(
void
)
const
{
return
FactMetaData
::
appSettingsDistanceUnitsString
();
}
/// Converts from square meters to the user specified area unit
Q_INVOKABLE
QVariant
squareMetersToAppSettingsAreaUnits
(
const
QVariant
&
meters
)
const
{
return
FactMetaData
::
squareMetersToAppSettingsAreaUnits
(
meters
);
}
/// Converts from user specified area unit to square meters
Q_INVOKABLE
QVariant
appSettingsAreaUnitsToSquareMeters
(
const
QVariant
&
area
)
const
{
return
FactMetaData
::
appSettingsAreaUnitsToSquareMeters
(
area
);
}
QString
appSettingsAreaUnitsString
(
void
)
const
{
return
FactMetaData
::
appSettingsAreaUnitsString
();
}
/// Returns the list of available logging category names.
Q_INVOKABLE
QStringList
loggingCategories
(
void
)
const
{
return
QGCLoggingCategoryRegister
::
instance
()
->
registeredCategories
();
}
...
...
@@ -161,6 +181,7 @@ public:
static
Fact
*
offlineEditingFirmwareType
(
void
);
static
Fact
*
distanceUnits
(
void
);
static
Fact
*
areaUnits
(
void
);
static
Fact
*
speedUnits
(
void
);
//-- TODO: Make this into an actual preference.
...
...
@@ -216,6 +237,8 @@ private:
static
FactMetaData
*
_offlineEditingFirmwareTypeMetaData
;
static
SettingsFact
*
_distanceUnitsFact
;
static
FactMetaData
*
_distanceUnitsMetaData
;
static
SettingsFact
*
_areaUnitsFact
;
static
FactMetaData
*
_areaUnitsMetaData
;
static
SettingsFact
*
_speedUnitsFact
;
static
FactMetaData
*
_speedUnitsMetaData
;
...
...
src/ui/preferences/GeneralSettings.qml
View file @
182f6b1a
...
...
@@ -138,6 +138,29 @@ QGCView {
}
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
QGCLabel
{
width
:
baseFontLabel
.
width
anchors.baseline
:
areaUnitsCombo
.
baseline
text
:
qsTr
(
"
Area units:
"
)
}
FactComboBox
{
id
:
areaUnitsCombo
width
:
_editFieldWidth
fact
:
QGroundControl
.
areaUnits
indexModel
:
false
}
QGCLabel
{
anchors.baseline
:
areaUnitsCombo
.
baseline
text
:
qsTr
(
"
(requires app restart)
"
)
}
}
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