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
38ae14b4
Commit
38ae14b4
authored
Jun 09, 2019
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
parent
00e8bb0e
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
26 additions
and
24 deletions
+26
-24
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+26
-24
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
38ae14b4
...
...
@@ -295,6 +295,11 @@ void APMFirmwarePlugin::_handleOutgoingParamSet(Vehicle* vehicle, LinkInterface*
mavlink_msg_param_set_decode
(
message
,
&
paramSet
);
if
(
!
_ardupilotComponentMap
[
paramSet
.
target_system
][
paramSet
.
target_component
])
{
// Message is targetted to non-ArduPilot firmware component, assume it uses current mavlink spec
return
;
}
paramUnion
.
param_float
=
paramSet
.
param_value
;
switch
(
paramSet
.
param_type
)
{
...
...
@@ -502,13 +507,10 @@ bool APMFirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_m
void
APMFirmwarePlugin
::
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
LinkInterface
*
outgoingLink
,
mavlink_message_t
*
message
)
{
// Only translate messages which come from ArduPilot code. All other components are expected to follow current mavlink spec.
if
(
_ardupilotComponentMap
[
vehicle
->
id
()][
message
->
compid
])
{
switch
(
message
->
msgid
)
{
case
MAVLINK_MSG_ID_PARAM_SET
:
_handleOutgoingParamSet
(
vehicle
,
outgoingLink
,
message
);
break
;
}
switch
(
message
->
msgid
)
{
case
MAVLINK_MSG_ID_PARAM_SET
:
_handleOutgoingParamSet
(
vehicle
,
outgoingLink
,
message
);
break
;
}
}
...
...
@@ -819,10 +821,10 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case
MAV_TYPE_COAXIAL
:
case
MAV_TYPE_HELICOPTER
:
if
(
vehicle
->
versionCompare
(
3
,
7
,
0
)
>=
0
)
{
// 3.7.0 and higher
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml"
);
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml"
);
}
if
(
vehicle
->
versionCompare
(
3
,
6
,
0
)
>=
0
)
{
// 3.6.0 and higher
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml"
);
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml"
);
}
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"
);
...
...
@@ -925,11 +927,11 @@ void APMFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_msg_set_position_target_local_ned_encode_chan
(
static_cast
<
uint8_t
>
(
mavlink
->
getSystemId
()),
static_cast
<
uint8_t
>
(
mavlink
->
getComponentId
()),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
static_cast
<
uint8_t
>
(
mavlink
->
getSystemId
()),
static_cast
<
uint8_t
>
(
mavlink
->
getComponentId
()),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
vehicle
->
sendMessageOnLink
(
vehicle
->
priorityLink
(),
msg
);
}
...
...
@@ -1058,11 +1060,11 @@ void APMFirmwarePlugin::_handleRCChannels(Vehicle* vehicle, mavlink_message_t* m
}
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_msg_rc_channels_encode_chan
(
static_cast
<
uint8_t
>
(
mavlink
->
getSystemId
()),
static_cast
<
uint8_t
>
(
mavlink
->
getComponentId
()),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
message
,
&
channels
);
static_cast
<
uint8_t
>
(
mavlink
->
getSystemId
()),
static_cast
<
uint8_t
>
(
mavlink
->
getComponentId
()),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
message
,
&
channels
);
}
void
APMFirmwarePlugin
::
_handleRCChannelsRaw
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
...
...
@@ -1075,10 +1077,10 @@ void APMFirmwarePlugin::_handleRCChannelsRaw(Vehicle* vehicle, mavlink_message_t
}
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_msg_rc_channels_raw_encode_chan
(
static_cast
<
uint8_t
>
(
mavlink
->
getSystemId
()),
static_cast
<
uint8_t
>
(
mavlink
->
getComponentId
()),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
message
,
&
channels
);
static_cast
<
uint8_t
>
(
mavlink
->
getSystemId
()),
static_cast
<
uint8_t
>
(
mavlink
->
getComponentId
()),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
message
,
&
channels
);
}
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