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
9021991d
Commit
9021991d
authored
May 07, 2013
by
Michael Carpenter
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Addition of more Q_PROPERTIES to UAS.cc, including visible GPS satellite count
parent
76ca1553
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
54 additions
and
12 deletions
+54
-12
UAS.cc
src/uas/UAS.cc
+13
-9
UAS.h
src/uas/UAS.h
+41
-3
No files found.
src/uas/UAS.cc
View file @
9021991d
...
...
@@ -81,9 +81,6 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
latitude_gps
(
0.0
),
longitude_gps
(
0.0
),
altitude_gps
(
0.0
),
roll
(
0.0
),
pitch
(
0.0
),
yaw
(
0.0
),
statusTimeout
(
new
QTimer
(
this
)),
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
receivedOverlayTimestamp
(
0.0
),
...
...
@@ -621,9 +618,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if
(
!
wrongComponent
)
{
lastAttitude
=
time
;
roll
=
QGC
::
limitAngleToPMPIf
(
attitude
.
roll
);
pitch
=
QGC
::
limitAngleToPMPIf
(
attitude
.
pitch
);
yaw
=
QGC
::
limitAngleToPMPIf
(
attitude
.
yaw
);
//roll = QGC::limitAngleToPMPIf(attitude.roll);
setRoll
(
QGC
::
limitAngleToPMPIf
(
attitude
.
roll
));
//pitch = QGC::limitAngleToPMPIf(attitude.pitch);
setPitch
(
QGC
::
limitAngleToPMPIf
(
attitude
.
pitch
));
//yaw = QGC::limitAngleToPMPIf(attitude.yaw);
setYaw
(
QGC
::
limitAngleToPMPIf
(
attitude
.
yaw
));
// // Emit in angles
...
...
@@ -643,7 +643,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// }
attitudeKnown
=
true
;
emit
attitudeChanged
(
this
,
roll
,
pitch
,
yaw
,
time
);
emit
attitudeChanged
(
this
,
getRoll
(),
getPitch
(),
getYaw
()
,
time
);
emit
attitudeSpeedChanged
(
uasId
,
attitude
.
rollspeed
,
attitude
.
pitchspeed
,
attitude
.
yawspeed
,
time
);
}
}
...
...
@@ -677,8 +677,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if
(
!
attitudeKnown
)
{
yaw
=
QGC
::
limitAngleToPMPId
((((
double
)
hud
.
heading
-
180.0
)
/
360.0
)
*
M_PI
);
emit
attitudeChanged
(
this
,
roll
,
pitch
,
yaw
,
time
);
//yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
setYaw
(
QGC
::
limitAngleToPMPId
((((
double
)
hud
.
heading
-
180.0
)
/
360.0
)
*
M_PI
));
emit
attitudeChanged
(
this
,
getRoll
(),
getPitch
(),
getYaw
(),
time
);
}
emit
altitudeChanged
(
uasId
,
hud
.
alt
);
...
...
@@ -777,9 +778,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
loc_type
=
0
;
}
emit
localizationChanged
(
this
,
loc_type
);
setSatelliteCount
(
pos
.
satellites_visible
);
if
(
pos
.
fix_type
>
2
)
{
latitude_gps
=
pos
.
lat
/
(
double
)
1E7
;
longitude_gps
=
pos
.
lon
/
(
double
)
1E7
;
altitude_gps
=
pos
.
alt
/
1000.0
;
...
...
@@ -822,6 +825,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
emit
gpsSatelliteStatusChanged
(
uasId
,
(
unsigned
char
)
pos
.
satellite_prn
[
i
],
(
unsigned
char
)
pos
.
satellite_elevation
[
i
],
(
unsigned
char
)
pos
.
satellite_azimuth
[
i
],
(
unsigned
char
)
pos
.
satellite_snr
[
i
],
static_cast
<
bool
>
(
pos
.
satellite_used
[
i
]));
}
setSatelliteCount
(
pos
.
satellites_visible
);
}
break
;
case
MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN
:
...
...
src/uas/UAS.h
View file @
9021991d
...
...
@@ -106,11 +106,12 @@ public:
Q_PROPERTY
(
double
latitude
READ
getLatitude
WRITE
setLatitude
NOTIFY
latitudeChanged
)
Q_PROPERTY
(
double
longitude
READ
getLongitude
WRITE
setLongitude
NOTIFY
longitudeChanged
)
Q_PROPERTY
(
double
altitude
READ
getAltitude
WRITE
setAltitude
NOTIFY
altitudeChanged
)
Q_PROPERTY
(
double
satelliteCount
READ
getSatelliteCount
WRITE
setSatelliteCount
NOTIFY
satelliteCountChanged
)
Q_PROPERTY
(
bool
isLocalPositionKnown
READ
localPositionKnown
)
Q_PROPERTY
(
bool
isGlobalPositionKnown
READ
globalPositionKnown
)
Q_PROPERTY
(
double
roll
READ
getRoll
)
Q_PROPERTY
(
double
pitch
READ
getPitch
)
Q_PROPERTY
(
double
yaw
READ
getYaw
)
Q_PROPERTY
(
double
roll
READ
getRoll
WRITE
setRoll
NOTIFY
rollChanged
)
Q_PROPERTY
(
double
pitch
READ
getPitch
WRITE
setPitch
NOTIFY
pitchChanged
)
Q_PROPERTY
(
double
yaw
READ
getYaw
WRITE
setYaw
NOTIFY
yawChanged
)
void
setLocalX
(
double
val
)
{
...
...
@@ -172,6 +173,18 @@ public:
{
return
altitude
;
}
void
setSatelliteCount
(
double
val
)
{
satelliteCount
=
val
;
emit
satelliteCountChanged
(
val
,
"satelliteCount"
);
}
double
getSatelliteCount
()
const
{
return
satelliteCount
;
}
virtual
bool
localPositionKnown
()
const
{
return
isLocalPositionKnown
;
...
...
@@ -181,14 +194,34 @@ public:
return
isGlobalPositionKnown
;
}
void
setRoll
(
double
val
)
{
roll
=
val
;
emit
rollChanged
(
val
,
"roll"
);
}
double
getRoll
()
const
{
return
roll
;
}
void
setPitch
(
double
val
)
{
pitch
=
val
;
emit
pitchChanged
(
val
,
"pitch"
);
}
double
getPitch
()
const
{
return
pitch
;
}
void
setYaw
(
double
val
)
{
yaw
=
val
;
emit
yawChanged
(
val
,
"yaw"
);
}
double
getYaw
()
const
{
return
yaw
;
...
...
@@ -329,6 +362,7 @@ protected: //COMMENTS FOR TEST UNIT
double
latitude
;
///< Global latitude as estimated by position estimator
double
longitude
;
///< Global longitude as estimated by position estimator
double
altitude
;
///< Global altitude as estimated by position estimator
double
satelliteCount
;
///< Number of satellites visible to raw GPS
bool
globalEstimatorActive
;
///< Global position estimator present, do not fall back to GPS raw for position
double
latitude_gps
;
///< Global latitude as estimated by raw GPS
double
longitude_gps
;
///< Global longitude as estimated by raw GPS
...
...
@@ -754,6 +788,10 @@ signals:
void
latitudeChanged
(
double
val
,
QString
name
);
void
altitudeChanged
(
double
val
,
QString
name
);
void
altitudeChanged
(
int
uasid
,
double
altitude
);
void
rollChanged
(
double
val
,
QString
name
);
void
pitchChanged
(
double
val
,
QString
name
);
void
yawChanged
(
double
val
,
QString
name
);
void
satelliteCountChanged
(
double
val
,
QString
name
);
protected:
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
...
...
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