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
f8eddb6d
Commit
f8eddb6d
authored
Apr 22, 2013
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fixed a bunch of smaller HIL issues, GPS COG is now correct
parent
0047d46b
Changes
3
Show whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
9 additions
and
2 deletions
+9
-2
QGCXPlaneLink.cc
src/comm/QGCXPlaneLink.cc
+1
-1
UAS.cc
src/uas/UAS.cc
+7
-1
UAS.h
src/uas/UAS.h
+1
-0
No files found.
src/comm/QGCXPlaneLink.cc
View file @
f8eddb6d
...
...
@@ -641,7 +641,7 @@ void QGCXPlaneLink::readBytes()
float
eph
=
0.3
;
float
epv
=
0.6
;
float
vel
=
sqrt
(
vx
*
vx
+
vy
*
vy
+
vz
*
vz
);
float
cog
=
yaw
;
float
cog
=
((
yaw
+
M_PI
)
/
M_PI
)
*
180.0
f
;
int
satellites
=
8
;
emit
sensorHilGpsChanged
(
QGC
::
groundTimeUsecs
(),
lat
,
lon
,
alt
,
gps_fix_type
,
eph
,
epv
,
vel
,
cog
,
satellites
);
...
...
src/uas/UAS.cc
View file @
f8eddb6d
...
...
@@ -111,7 +111,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
lastVoltageWarning
(
0
),
lastNonNullTime
(
0
),
onboardTimeOffsetInvalidCount
(
0
),
hilEnabled
(
false
)
hilEnabled
(
false
),
lastSendTimeGPS
(
0
)
{
for
(
unsigned
int
i
=
0
;
i
<
255
;
++
i
)
...
...
@@ -2785,11 +2786,16 @@ void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, fl
void
UAS
::
sendHilGps
(
quint64
time_us
,
double
lat
,
double
lon
,
double
alt
,
int
fix_type
,
float
eph
,
float
epv
,
float
vel
,
float
cog
,
int
satellites
)
{
// Only send at 10 Hz max rate
if
(
QGC
::
groundTimeMilliseconds
()
-
lastSendTimeGPS
<
100
)
return
;
if
(
this
->
mode
&
MAV_MODE_FLAG_HIL_ENABLED
)
{
mavlink_message_t
msg
;
mavlink_msg_gps_raw_int_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
time_us
,
fix_type
,
lat
*
1e7
,
lon
*
1e7
,
alt
*
1e3
,
eph
*
1e2
,
epv
*
1e2
,
vel
*
1e2
,
cog
*
1e2
,
satellites
);
lastSendTimeGPS
=
QGC
::
groundTimeMilliseconds
();
sendMessage
(
msg
);
}
else
...
...
src/uas/UAS.h
View file @
f8eddb6d
...
...
@@ -704,6 +704,7 @@ protected:
unsigned
int
onboardTimeOffsetInvalidCount
;
///< Count when the offboard time offset estimation seemed wrong
bool
hilEnabled
;
///< Set to true if HIL mode is enabled from GCS (UAS might be in HIL even if this flag is not set, this defines the GCS HIL setting)
bool
sensorHil
;
///< True if sensor HIL is enabled
quint64
lastSendTimeGPS
;
///< Last HIL GPS message sent
protected
slots
:
/** @brief Write settings to disk */
...
...
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