Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
2c3a43b0
Commit
2c3a43b0
authored
May 02, 2017
by
Don Gagne
Committed by
GitHub
May 02, 2017
Browse files
Merge pull request #5076 from DonLakeFlyer/YawSetting
Plan: Show/Hide Heading in waypoint item based on yaw to next wpt setting
parents
bc0f7b12
4beacbc9
Changes
4
Hide whitespace changes
Inline
Side-by-side
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
2c3a43b0
...
...
@@ -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 @
2c3a43b0
...
...
@@ -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/MissionController.cc
View file @
2c3a43b0
...
...
@@ -1044,7 +1044,7 @@ void MissionController::_recalcMissionFlightStatus()
}
// Look for gimbal change
if
(
_
controll
erVehicle
->
vehicleYawsToNextWaypointInMission
())
{
if
(
_
manag
erVehicle
->
vehicleYawsToNextWaypointInMission
())
{
// We current only support gimbal display in this mode
double
gimbalYaw
=
item
->
specifiedGimbalYaw
();
if
(
!
qIsNaN
(
gimbalYaw
))
{
...
...
@@ -1371,7 +1371,7 @@ void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
_managerVehicle
=
managerVehicle
;
if
(
!
_managerVehicle
)
{
qWarning
()
<<
"
RallyPoint
Controller::managerVehicleChanged managerVehicle=NULL"
;
qWarning
()
<<
"
Mission
Controller::managerVehicleChanged managerVehicle=NULL"
;
return
;
}
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
2c3a43b0
...
...
@@ -446,6 +446,17 @@ void SimpleMissionItem::_rebuildNaNFacts(void)
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
)
&&
(
i
==
4
)
&&
firmwareVehicle
->
firmwarePlugin
()
->
vehicleYawsToNextWaypointInMission
(
firmwareVehicle
);
if
(
hideWaypointHeading
)
{
continue
;
}
Fact
*
paramFact
=
rgParamFacts
[
i
-
1
];
FactMetaData
*
paramMetaData
=
rgParamMetaData
[
i
-
1
];
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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