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
9c270151
Commit
9c270151
authored
May 14, 2013
by
Michael Carpenter
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Change in how APM requests data updates on connect
parent
7f4cb987
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
9 additions
and
20 deletions
+9
-20
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+0
-19
ArduPilotMegaMAV.cc
src/uas/ArduPilotMegaMAV.cc
+9
-1
No files found.
src/comm/MAVLinkProtocol.cc
View file @
9c270151
...
...
@@ -384,25 +384,6 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// Create a new UAS object
uas
=
QGCMAVLinkUASFactory
::
createUAS
(
this
,
link
,
message
.
sysid
,
&
heartbeat
);
//This is the first instance of this UAS being known, request update rates:
mavlink_message_t
newmsg
;
mavlink_msg_request_data_stream_pack
(
1
,
255
,
&
newmsg
,
message
.
sysid
,
message
.
compid
,
2
,
2
,
1
);
// Extended Status, 2hz
sendMessage
(
link
,
newmsg
);
mavlink_msg_request_data_stream_pack
(
1
,
255
,
&
newmsg
,
message
.
sysid
,
message
.
compid
,
6
,
3
,
1
);
//Position 3hz
sendMessage
(
link
,
newmsg
);
mavlink_msg_request_data_stream_pack
(
1
,
255
,
&
newmsg
,
message
.
sysid
,
message
.
compid
,
10
,
10
,
1
);
//Extra 1 10hz
sendMessage
(
link
,
newmsg
);
mavlink_msg_request_data_stream_pack
(
1
,
255
,
&
newmsg
,
message
.
sysid
,
message
.
compid
,
11
,
10
,
1
);
//Extra 2 10hz
sendMessage
(
link
,
newmsg
);
mavlink_msg_request_data_stream_pack
(
1
,
255
,
&
newmsg
,
message
.
sysid
,
message
.
compid
,
12
,
2
,
1
);
//Extra 3 2hz
sendMessage
(
link
,
newmsg
);
mavlink_msg_request_data_stream_pack
(
1
,
255
,
&
newmsg
,
message
.
sysid
,
message
.
compid
,
1
,
2
,
1
);
//Raw Sensors 2hz
sendMessage
(
link
,
newmsg
);
mavlink_msg_request_data_stream_pack
(
1
,
255
,
&
newmsg
,
message
.
sysid
,
message
.
compid
,
3
,
2
,
1
);
//RC Channels 2hz
sendMessage
(
link
,
newmsg
);
}
// Only count message if UAS exists for this message
...
...
src/uas/ArduPilotMegaMAV.cc
View file @
9c270151
...
...
@@ -31,8 +31,16 @@ ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id) :
UAS
(
mavlink
,
id
)
//,
// place other initializers here
{
//This does not seem to work. Manually request each stream type at a specified rate.
// Ask for all streams at 4 Hz
enableAllDataTransmission
(
4
);
//enableAllDataTransmission(4);
enableExtendedSystemStatusTransmission
(
2
);
enablePositionTransmission
(
3
);
enableExtra1Transmission
(
10
);
enableExtra2Transmission
(
10
);
enableExtra3Transmission
(
2
);
enableRawSensorDataTransmission
(
2
);
enableRCChannelDataTransmission
(
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