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
9e887c44
Commit
9e887c44
authored
Aug 12, 2011
by
LM
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Minor compile fixes
parent
9a705c22
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
21 additions
and
7 deletions
+21
-7
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+1
-1
UAS.cc
src/uas/UAS.cc
+20
-5
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+0
-1
No files found.
src/comm/MAVLinkSimulationLink.cc
View file @
9e887c44
...
...
@@ -409,7 +409,7 @@ void MAVLinkSimulationLink::mainloop()
// streampointer += bufferlength;
// GLOBAL POSITION
mavlink_msg_global_position_int_pack
(
systemId
,
componentId
,
&
ret
,
(
473780.28137103
+
(
x
))
*
1E3
,
(
85489.9892510421
+
(
y
))
*
1E3
,
(
z
+
550.0
)
*
1000.0
,
xSpeed
,
ySpeed
,
zSpeed
);
mavlink_msg_global_position_int_pack
(
systemId
,
componentId
,
&
ret
,
(
473780.28137103
+
(
x
))
*
1E3
,
(
85489.9892510421
+
(
y
))
*
1E3
,
(
z
+
550.0
)
*
1000.0
,
xSpeed
,
ySpeed
,
zSpeed
,
yaw
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
ret
);
//add data into datastream
memcpy
(
stream
+
streampointer
,
buffer
,
bufferlength
);
...
...
src/uas/UAS.cc
View file @
9e887c44
...
...
@@ -75,7 +75,7 @@ paramsOnceRequested(false),
airframe
(
0
),
attitudeKnown
(
false
),
paramManager
(
NULL
),
attitudeStamped
(
tru
e
),
attitudeStamped
(
fals
e
),
lastAttitude
(
0
)
{
color
=
UASInterface
::
getNextColor
();
...
...
@@ -682,7 +682,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if
(
pos
.
fix_type
>
0
)
{
emit
globalPositionChanged
(
this
,
pos
.
lat
/
(
double
)
1E7
,
pos
.
lon
/
(
double
)
1E7
,
pos
.
alt
/
1000.0
,
time
);
emit
valueChanged
(
uasId
,
"gps speed"
,
"m/s"
,
pos
.
v
,
time
);
emit
valueChanged
(
uasId
,
"gps speed"
,
"m/s"
,
pos
.
v
el
,
time
);
latitude
=
pos
.
lat
/
(
double
)
1E7
;
longitude
=
pos
.
lon
/
(
double
)
1E7
;
altitude
=
pos
.
alt
/
1000.0
;
...
...
@@ -696,12 +696,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
emit
valueChanged
(
uasId
,
"altitude"
,
"m"
,
pos
.
alt
/
(
double
)
1E3
,
time
);
// Smaller than threshold and not NaN
if
(
pos
.
v
<
1000000
&&
pos
.
v
==
pos
.
v
)
{
emit
valueChanged
(
uasId
,
"speed"
,
"m/s"
,
pos
.
v
,
time
);
float
vel
=
pos
.
vel
/
100.0
f
;
if
(
vel
<
1000000
&&
!
isnan
(
vel
)
&&
!
isinf
(
vel
))
{
emit
valueChanged
(
uasId
,
"speed"
,
"m/s"
,
vel
,
time
);
//qDebug() << "GOT GPS RAW";
// emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
}
else
{
emit
textMessageReceived
(
uasId
,
message
.
compid
,
255
,
QString
(
"GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s"
).
arg
(
pos
.
v
));
emit
textMessageReceived
(
uasId
,
message
.
compid
,
255
,
QString
(
"GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s"
).
arg
(
vel
));
}
}
}
...
...
@@ -854,6 +857,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
waypointManager
.
handleWaypointCount
(
message
.
sysid
,
message
.
compid
,
wpc
.
count
);
}
else
{
qDebug
()
<<
"Got waypoint message, but was not for me"
;
}
}
break
;
...
...
@@ -866,6 +873,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
waypointManager
.
handleWaypoint
(
message
.
sysid
,
message
.
compid
,
&
wp
);
}
else
{
qDebug
()
<<
"Got waypoint message, but was not for me"
;
}
}
break
;
...
...
@@ -888,6 +899,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
waypointManager
.
handleWaypointRequest
(
message
.
sysid
,
message
.
compid
,
&
wpr
);
}
else
{
qDebug
()
<<
"Got waypoint message, but was not for me"
;
}
}
break
;
...
...
src/uas/UASWaypointManager.cc
View file @
9e887c44
...
...
@@ -32,7 +32,6 @@ This file is part of the QGROUNDCONTROL project
#include "UASWaypointManager.h"
#include "UAS.h"
#include "mavlink_types.h"
//#include "MainWindow.h"
#define PROTOCOL_TIMEOUT_MS 2000 ///< maximum time to wait for pending messages until timeout
#define PROTOCOL_DELAY_MS 40 ///< minimum delay between sent messages
...
...
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