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
dc848ceb
Commit
dc848ceb
authored
May 02, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Show/Hide Heading in waypoint item based on yaw to next wpt setting
parent
08f54ff7
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
23 additions
and
7 deletions
+23
-7
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+7
-3
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+7
-3
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+9
-1
No files found.
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
dc848ceb
...
...
@@ -237,9 +237,13 @@ QString ArduCopterFirmwarePlugin::geoFenceRadiusParam(Vehicle* vehicle)
bool
ArduCopterFirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
{
if
(
!
vehicle
->
isOfflineEditingVehicle
()
&&
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"WP_YAW_BEHAVIOR"
)))
{
Fact
*
yawMode
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"WP_YAW_BEHAVIOR"
));
return
yawMode
&&
yawMode
->
rawValue
().
toInt
()
!=
0
;
if
(
vehicle
->
isOfflineEditingVehicle
())
{
return
FirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
vehicle
);
}
else
{
if
(
vehicle
->
multiRotor
()
&&
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"WP_YAW_BEHAVIOR"
)))
{
Fact
*
yawMode
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"WP_YAW_BEHAVIOR"
));
return
yawMode
&&
yawMode
->
rawValue
().
toInt
()
!=
0
;
}
}
return
true
;
}
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
dc848ceb
...
...
@@ -518,9 +518,13 @@ void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_messag
bool
PX4FirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
{
if
(
!
vehicle
->
isOfflineEditingVehicle
()
&&
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"MIS_YAWMODE"
)))
{
Fact
*
yawMode
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"MIS_YAWMODE"
));
return
yawMode
&&
yawMode
->
rawValue
().
toInt
()
==
1
;
if
(
vehicle
->
isOfflineEditingVehicle
())
{
return
FirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
vehicle
);
}
else
{
if
(
vehicle
->
multiRotor
()
&&
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"MIS_YAWMODE"
)))
{
Fact
*
yawMode
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"MIS_YAWMODE"
));
return
yawMode
&&
yawMode
->
rawValue
().
toInt
()
==
1
;
}
}
return
true
;
}
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
dc848ceb
...
...
@@ -445,7 +445,15 @@ void SimpleMissionItem::_rebuildNaNFacts(void)
for
(
int
i
=
1
;
i
<=
7
;
i
++
)
{
const
MissionCmdParamInfo
*
paramInfo
=
uiInfo
->
getParamInfo
(
i
);
if
(
paramInfo
&&
paramInfo
->
nanUnchanged
())
{
// Show hide Heading field on waypoint based on vehicle yaw to next waypoint setting. This needs to come from the actual vehicle if it exists
// and not _vehicle which is always offline.
Vehicle
*
firmwareVehicle
=
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
activeVehicle
();
if
(
!
firmwareVehicle
)
{
firmwareVehicle
=
_vehicle
;
}
bool
hideWaypointHeading
=
command
==
MAV_CMD_NAV_WAYPOINT
&&
firmwareVehicle
->
firmwarePlugin
()
->
vehicleYawsToNextWaypointInMission
(
firmwareVehicle
);
if
(
paramInfo
&&
paramInfo
->
nanUnchanged
()
&&
!
hideWaypointHeading
)
{
Fact
*
paramFact
=
rgParamFacts
[
i
-
1
];
FactMetaData
*
paramMetaData
=
rgParamMetaData
[
i
-
1
];
...
...
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