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
5dad474e
Commit
5dad474e
authored
Jan 23, 2011
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Added named value packet
parent
31f97dd6
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
65 additions
and
3 deletions
+65
-3
MAVLinkSimulationMAV.cc
src/comm/MAVLinkSimulationMAV.cc
+55
-0
MAVLinkSimulationWaypointPlanner.cc
src/comm/MAVLinkSimulationWaypointPlanner.cc
+0
-1
UAS.cc
src/uas/UAS.cc
+10
-2
No files found.
src/comm/MAVLinkSimulationMAV.cc
View file @
5dad474e
...
...
@@ -158,6 +158,61 @@ void MAVLinkSimulationMAV::mainloop()
// 25 Hz execution
if
(
timer25Hz
<=
0
)
{
// Send a named value with name "FLOAT" and 0.5f as value
// The message container to be used for sending
mavlink_message_t
ret
;
// The C-struct holding the data to be sent
mavlink_named_value_float_t
val
;
// Fill in the data
// Name of the value, maximum 10 characters
// see full message specs at:
// http://pixhawk.ethz.ch/wiki/mavlink/
strcpy
(
val
.
name
,
"FLOAT"
);
// Value, in this case 0.5
val
.
value
=
0.5
f
;
// Encode the data (adding header and checksums, etc.)
mavlink_msg_named_value_float_encode
(
systemid
,
MAV_COMP_ID_IMU
,
&
ret
,
&
val
);
// And send it
link
->
sendMAVLinkMessage
(
&
ret
);
// MICROCONTROLLER SEND CODE:
// uint8_t buf[MAVLINK_MAX_PACKET_LEN];
// int16_t len = mavlink_msg_to_send_buffer(buf, &ret);
// uart0_transmit(buf, len);
// SEND INTEGER VALUE
// We are reusing the "mavlink_message_t ret"
// message buffer
// The C-struct holding the data to be sent
mavlink_named_value_int_t
valint
;
// Fill in the data
// Name of the value, maximum 10 characters
// see full message specs at:
// http://pixhawk.ethz.ch/wiki/mavlink/
strcpy
(
valint
.
name
,
"INTEGER"
);
// Value, in this case 18000
valint
.
value
=
18000
;
// Encode the data (adding header and checksums, etc.)
mavlink_msg_named_value_int_encode
(
systemid
,
MAV_COMP_ID_IMU
,
&
ret
,
&
valint
);
// And send it
link
->
sendMAVLinkMessage
(
&
ret
);
// MICROCONTROLLER SEND CODE:
// uint8_t buf[MAVLINK_MAX_PACKET_LEN];
// int16_t len = mavlink_msg_to_send_buffer(buf, &ret);
// uart0_transmit(buf, len);
timer25Hz
=
2
;
}
...
...
src/comm/MAVLinkSimulationWaypointPlanner.cc
View file @
5dad474e
...
...
@@ -563,7 +563,6 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
case
MAVLINK_MSG_ID_GLOBAL_POSITION_INT
:
{
qDebug
()
<<
"GOT GLOBAL POS"
<<
"sys:"
<<
msg
->
sysid
<<
"wpid"
<<
current_active_wp_id
<<
"wpsize"
<<
waypoints
->
size
();
if
(
msg
->
sysid
==
systemid
&&
current_active_wp_id
<
waypoints
->
size
())
{
mavlink_waypoint_t
*
wp
=
waypoints
->
at
(
current_active_wp_id
);
...
...
src/uas/UAS.cc
View file @
5dad474e
...
...
@@ -162,11 +162,15 @@ void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
if
(
message
.
msgid
==
MAVLINK_MSG_ID_NAMED_VALUE_FLOAT
)
{
mavlink_named_value_float_t
val
;
mavlink_msg_named_value_float_decode
(
&
message
,
&
val
);
emit
valueChanged
(
this
->
getUASID
(),
QString
(
val
.
name
),
tr
(
"raw"
),
val
.
value
,
getUnixTime
(
0
));
}
else
if
(
message
.
msgid
==
MAVLINK_MSG_ID_NAMED_VALUE_INT
)
{
mavlink_named_value_int_t
val
;
mavlink_msg_named_value_int_decode
(
&
message
,
&
val
);
emit
valueChanged
(
this
->
getUASID
(),
QString
(
val
.
name
),
tr
(
"raw"
),
(
float
)
val
.
value
,
getUnixTime
(
0
));
}
}
...
...
@@ -190,6 +194,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
QString
uasState
;
QString
stateDescription
;
QString
patternPath
;
// Receive named value message
receiveMessageNamedValue
(
message
);
switch
(
message
.
msgid
)
{
case
MAVLINK_MSG_ID_HEARTBEAT
:
...
...
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