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
4d65ea29
Commit
4d65ea29
authored
Jul 04, 2016
by
Don Gagne
Committed by
GitHub
Jul 04, 2016
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #3721 from dagar/wind
mavlink WIND_COV -> windFactGroup
parents
32d572be
34dc935a
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
17 additions
and
0 deletions
+17
-0
Vehicle.cc
src/Vehicle/Vehicle.cc
+16
-0
Vehicle.h
src/Vehicle/Vehicle.h
+1
-0
No files found.
src/Vehicle/Vehicle.cc
View file @
4d65ea29
...
...
@@ -443,6 +443,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case
MAVLINK_MSG_ID_AUTOPILOT_VERSION
:
_handleAutopilotVersion
(
message
);
break
;
case
MAVLINK_MSG_ID_WIND_COV
:
_handleWindCov
(
message
);
break
;
// Following are ArduPilot dialect messages
...
...
@@ -542,6 +545,19 @@ void Vehicle::_handleVibration(mavlink_message_t& message)
_vibrationFactGroup
.
clipCount3
()
->
setRawValue
(
vibration
.
clipping_2
);
}
void
Vehicle
::
_handleWindCov
(
mavlink_message_t
&
message
)
{
mavlink_wind_cov_t
wind
;
mavlink_msg_wind_cov_decode
(
&
message
,
&
wind
);
float
direction
=
qRadiansToDegrees
(
qAtan2
(
wind
.
wind_y
,
wind
.
wind_x
));
float
speed
=
qSqrt
(
qPow
(
wind
.
wind_x
,
2
)
+
qPow
(
wind
.
wind_y
,
2
));
_windFactGroup
.
direction
()
->
setRawValue
(
direction
);
_windFactGroup
.
speed
()
->
setRawValue
(
speed
);
_windFactGroup
.
verticalSpeed
()
->
setRawValue
(
0
);
}
void
Vehicle
::
_handleWind
(
mavlink_message_t
&
message
)
{
mavlink_wind_t
wind
;
...
...
src/Vehicle/Vehicle.h
View file @
4d65ea29
...
...
@@ -639,6 +639,7 @@ private:
void
_handleRCChannelsRaw
(
mavlink_message_t
&
message
);
void
_handleBatteryStatus
(
mavlink_message_t
&
message
);
void
_handleSysStatus
(
mavlink_message_t
&
message
);
void
_handleWindCov
(
mavlink_message_t
&
message
);
void
_handleWind
(
mavlink_message_t
&
message
);
void
_handleVibration
(
mavlink_message_t
&
message
);
void
_handleExtendedSysState
(
mavlink_message_t
&
message
);
...
...
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