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
9597d772
Commit
9597d772
authored
Aug 26, 2010
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Added global position
parent
8438b4d5
Changes
1
Show whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
8 additions
and
1 deletion
+8
-1
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+8
-1
No files found.
src/comm/MAVLinkSimulationLink.cc
View file @
9597d772
...
@@ -404,13 +404,20 @@ void MAVLinkSimulationLink::mainloop()
...
@@ -404,13 +404,20 @@ void MAVLinkSimulationLink::mainloop()
memcpy
(
stream
+
streampointer
,
buffer
,
bufferlength
);
memcpy
(
stream
+
streampointer
,
buffer
,
bufferlength
);
streampointer
+=
bufferlength
;
streampointer
+=
bufferlength
;
//
Send back new position
//
GPS RAW
mavlink_msg_gps_raw_pack
(
systemId
,
componentId
,
&
ret
,
0
,
3
,
47.376417
+
x
*
0.001
f
,
8.548103
+
y
*
0.001
f
,
z
,
0
,
0
,
2.5
f
,
0.1
f
);
mavlink_msg_gps_raw_pack
(
systemId
,
componentId
,
&
ret
,
0
,
3
,
47.376417
+
x
*
0.001
f
,
8.548103
+
y
*
0.001
f
,
z
,
0
,
0
,
2.5
f
,
0.1
f
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
ret
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
ret
);
//add data into datastream
//add data into datastream
memcpy
(
stream
+
streampointer
,
buffer
,
bufferlength
);
memcpy
(
stream
+
streampointer
,
buffer
,
bufferlength
);
streampointer
+=
bufferlength
;
streampointer
+=
bufferlength
;
// GLOBAL POSITION
mavlink_msg_global_position_pack
(
systemId
,
componentId
,
&
ret
,
0
,
3
,
47.376417
+
x
*
0.001
f
,
8.548103
+
y
*
0.001
f
,
z
,
0
,
0
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
ret
);
//add data into datastream
memcpy
(
stream
+
streampointer
,
buffer
,
bufferlength
);
streampointer
+=
bufferlength
;
static
int
rcCounter
=
0
;
static
int
rcCounter
=
0
;
if
(
rcCounter
==
2
)
if
(
rcCounter
==
2
)
{
{
...
...
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