Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
72e5769b
Commit
72e5769b
authored
Jul 25, 2017
by
Jacob Walser
Browse files
Add gps coordinates to vehicle gps factgroup
parent
667c1e12
Changes
3
Hide whitespace changes
Inline
Side-by-side
src/Vehicle/GPSFact.json
View file @
72e5769b
[
{
"name"
:
"lat"
,
"shortDescription"
:
"Latitude"
,
"type"
:
"double"
,
"decimalPlaces"
:
7
},
{
"name"
:
"lon"
,
"shortDescription"
:
"Longitude"
,
"type"
:
"double"
,
"decimalPlaces"
:
7
},
{
"name"
:
"hdop"
,
"shortDescription"
:
"HDOP"
,
...
...
src/Vehicle/Vehicle.cc
View file @
72e5769b
...
...
@@ -680,6 +680,8 @@ void Vehicle::_handleGpsRawInt(mavlink_message_t& message)
}
}
_gpsFactGroup
.
lat
()
->
setRawValue
(
gpsRawInt
.
lat
*
1e-7
);
_gpsFactGroup
.
lon
()
->
setRawValue
(
gpsRawInt
.
lon
*
1e-7
);
_gpsFactGroup
.
count
()
->
setRawValue
(
gpsRawInt
.
satellites_visible
==
255
?
0
:
gpsRawInt
.
satellites_visible
);
_gpsFactGroup
.
hdop
()
->
setRawValue
(
gpsRawInt
.
eph
==
UINT16_MAX
?
std
::
numeric_limits
<
double
>::
quiet_NaN
()
:
gpsRawInt
.
eph
/
100.0
);
_gpsFactGroup
.
vdop
()
->
setRawValue
(
gpsRawInt
.
epv
==
UINT16_MAX
?
std
::
numeric_limits
<
double
>::
quiet_NaN
()
:
gpsRawInt
.
epv
/
100.0
);
...
...
@@ -2458,6 +2460,8 @@ void Vehicle::triggerCamera(void)
1.0
);
// test shot flag
}
const
char
*
VehicleGPSFactGroup
::
_latFactName
=
"lat"
;
const
char
*
VehicleGPSFactGroup
::
_lonFactName
=
"lon"
;
const
char
*
VehicleGPSFactGroup
::
_hdopFactName
=
"hdop"
;
const
char
*
VehicleGPSFactGroup
::
_vdopFactName
=
"vdop"
;
const
char
*
VehicleGPSFactGroup
::
_courseOverGroundFactName
=
"courseOverGround"
;
...
...
@@ -2466,18 +2470,24 @@ const char* VehicleGPSFactGroup::_lockFactName = "lock";
VehicleGPSFactGroup
::
VehicleGPSFactGroup
(
QObject
*
parent
)
:
FactGroup
(
1000
,
":/json/Vehicle/GPSFact.json"
,
parent
)
,
_latFact
(
0
,
_latFactName
,
FactMetaData
::
valueTypeDouble
)
,
_lonFact
(
0
,
_lonFactName
,
FactMetaData
::
valueTypeDouble
)
,
_hdopFact
(
0
,
_hdopFactName
,
FactMetaData
::
valueTypeDouble
)
,
_vdopFact
(
0
,
_vdopFactName
,
FactMetaData
::
valueTypeDouble
)
,
_courseOverGroundFact
(
0
,
_courseOverGroundFactName
,
FactMetaData
::
valueTypeDouble
)
,
_countFact
(
0
,
_countFactName
,
FactMetaData
::
valueTypeInt32
)
,
_lockFact
(
0
,
_lockFactName
,
FactMetaData
::
valueTypeInt32
)
{
_addFact
(
&
_latFact
,
_latFactName
);
_addFact
(
&
_lonFact
,
_lonFactName
);
_addFact
(
&
_hdopFact
,
_hdopFactName
);
_addFact
(
&
_vdopFact
,
_vdopFactName
);
_addFact
(
&
_courseOverGroundFact
,
_courseOverGroundFactName
);
_addFact
(
&
_lockFact
,
_lockFactName
);
_addFact
(
&
_countFact
,
_countFactName
);
_latFact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
_lonFact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
_hdopFact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
_vdopFact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
_courseOverGroundFact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
...
...
src/Vehicle/Vehicle.h
View file @
72e5769b
...
...
@@ -113,18 +113,24 @@ class VehicleGPSFactGroup : public FactGroup
public:
VehicleGPSFactGroup
(
QObject
*
parent
=
NULL
);
Q_PROPERTY
(
Fact
*
lat
READ
lat
CONSTANT
)
Q_PROPERTY
(
Fact
*
lon
READ
lon
CONSTANT
)
Q_PROPERTY
(
Fact
*
hdop
READ
hdop
CONSTANT
)
Q_PROPERTY
(
Fact
*
vdop
READ
vdop
CONSTANT
)
Q_PROPERTY
(
Fact
*
courseOverGround
READ
courseOverGround
CONSTANT
)
Q_PROPERTY
(
Fact
*
count
READ
count
CONSTANT
)
Q_PROPERTY
(
Fact
*
lock
READ
lock
CONSTANT
)
Fact
*
lat
(
void
)
{
return
&
_latFact
;
}
Fact
*
lon
(
void
)
{
return
&
_lonFact
;
}
Fact
*
hdop
(
void
)
{
return
&
_hdopFact
;
}
Fact
*
vdop
(
void
)
{
return
&
_vdopFact
;
}
Fact
*
courseOverGround
(
void
)
{
return
&
_courseOverGroundFact
;
}
Fact
*
count
(
void
)
{
return
&
_countFact
;
}
Fact
*
lock
(
void
)
{
return
&
_lockFact
;
}
static
const
char
*
_latFactName
;
static
const
char
*
_lonFactName
;
static
const
char
*
_hdopFactName
;
static
const
char
*
_vdopFactName
;
static
const
char
*
_courseOverGroundFactName
;
...
...
@@ -132,6 +138,8 @@ public:
static
const
char
*
_lockFactName
;
private:
Fact
_latFact
;
Fact
_lonFact
;
Fact
_hdopFact
;
Fact
_vdopFact
;
Fact
_courseOverGroundFact
;
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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