Browse Source

Merge pull request #7613 from Aeronavics/compass_home_n_COG

Feature Proposal - Home Heading / COG Angle / Next WP Heading in Compass
QGC4.4
Don Gagne 6 years ago committed by GitHub
parent
commit
313ce21f85
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 1
      ChangeLog.md
  2. 2
      qgcimages.qrc
  3. 2
      src/FlightDisplay/FlightDisplayView.qml
  4. 1
      src/FlightDisplay/MultiVehicleList.qml
  5. 53
      src/FlightMap/Images/cOGPointer.svg
  6. 50
      src/FlightMap/Images/compassDottedLine.svg
  7. 89
      src/FlightMap/Widgets/QGCCompassWidget.qml
  8. 2
      src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml
  9. 12
      src/Settings/FlyView.SettingsGroup.json
  10. 2
      src/Settings/FlyViewSettings.cc
  11. 2
      src/Settings/FlyViewSettings.h
  12. 23
      src/Vehicle/Vehicle.cc
  13. 5
      src/Vehicle/Vehicle.h
  14. 7
      src/Vehicle/VehicleFact.json
  15. 15
      src/ui/preferences/GeneralSettings.qml

1
ChangeLog.md

@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build ### 3.6.0 - Daily Build
* Compass Instrument: Add indicators for Home, COG and Next Waypoint headings.
* Log Replay: Support changing speed of playback * Log Replay: Support changing speed of playback
* Basic object avoidance added to vehicles. * Basic object avoidance added to vehicles.
* Added ability to set a joystick button to be single action or repeated action while the button is held down. * Added ability to set a joystick button to be single action or repeated action while the button is held down.

2
qgcimages.qrc

@ -69,6 +69,8 @@
<file alias="CogWheel.svg">src/MissionManager/CogWheel.svg</file> <file alias="CogWheel.svg">src/MissionManager/CogWheel.svg</file>
<file alias="compassInstrumentArrow.svg">src/FlightMap/Images/compassInstrumentArrow.svg</file> <file alias="compassInstrumentArrow.svg">src/FlightMap/Images/compassInstrumentArrow.svg</file>
<file alias="compassInstrumentDial.svg">src/FlightMap/Images/compassInstrumentDial.svg</file> <file alias="compassInstrumentDial.svg">src/FlightMap/Images/compassInstrumentDial.svg</file>
<file alias="compassDottedLine.svg">src/FlightMap/Images/compassDottedLine.svg</file>
<file alias="cOGPointer.svg">src/FlightMap/Images/cOGPointer.svg</file>
<file alias="Connect.svg">src/ui/toolbar/Images/Connect.svg</file> <file alias="Connect.svg">src/ui/toolbar/Images/Connect.svg</file>
<file alias="crossHair.svg">src/FlightMap/Images/crossHair.svg</file> <file alias="crossHair.svg">src/FlightMap/Images/crossHair.svg</file>
<file alias="DatalinkLoss.svg">src/AutoPilotPlugins/PX4/Images/DatalinkLoss.svg</file> <file alias="DatalinkLoss.svg">src/AutoPilotPlugins/PX4/Images/DatalinkLoss.svg</file>

2
src/FlightDisplay/FlightDisplayView.qml

@ -494,7 +494,6 @@ Item {
anchors.topMargin: ScreenTools.toolbarHeight + _margins anchors.topMargin: ScreenTools.toolbarHeight + _margins
anchors.rightMargin: _margins anchors.rightMargin: _margins
anchors.right: parent.right anchors.right: parent.right
anchors.top: parent.top
spacing: ScreenTools.defaultFontPixelWidth spacing: ScreenTools.defaultFontPixelWidth
z: _mapAndVideo.z + 4 z: _mapAndVideo.z + 4
visible: QGroundControl.multiVehicleManager.vehicles.count > 1 && QGroundControl.corePlugin.options.enableMultiVehicleList visible: QGroundControl.multiVehicleManager.vehicles.count > 1 && QGroundControl.corePlugin.options.enableMultiVehicleList
@ -519,6 +518,7 @@ Item {
anchors.left: parent.left anchors.left: parent.left
anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
anchors.top: singleMultiSelector.visible? singleMultiSelector.bottom:undefined
useLightColors: isBackgroundDark useLightColors: isBackgroundDark
missionController: _missionController missionController: _missionController
visible: singleVehicleView.checked && !QGroundControl.videoManager.fullScreen visible: singleVehicleView.checked && !QGroundControl.videoManager.fullScreen

1
src/FlightDisplay/MultiVehicleList.qml

@ -135,6 +135,7 @@ Item {
QGCCompassWidget { QGCCompassWidget {
size: _widgetHeight size: _widgetHeight
usedByMultipleVehicleList: true
vehicle: _vehicle vehicle: _vehicle
} }

53
src/FlightMap/Images/cOGPointer.svg

@ -0,0 +1,53 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<!-- Generator: Adobe Illustrator 18.1.1, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg
xmlns:dc="http://purl.org/dc/elements/1.1/"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns="http://www.w3.org/2000/svg"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
version="1.1"
id="Layer_3"
x="0px"
y="0px"
viewBox="0 0 288 288"
enable-background="new 0 0 288 288"
xml:space="preserve"
inkscape:version="0.91 r13725"
sodipodi:docname="cOGPointer.svg"><metadata
id="metadata11"><rdf:RDF><cc:Work
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /><dc:title /></cc:Work></rdf:RDF></metadata><defs
id="defs9" /><sodipodi:namedview
pagecolor="#ffffff"
bordercolor="#666666"
borderopacity="1"
objecttolerance="10"
gridtolerance="10"
guidetolerance="10"
inkscape:pageopacity="0"
inkscape:pageshadow="2"
inkscape:window-width="1918"
inkscape:window-height="1059"
id="namedview7"
showgrid="false"
inkscape:zoom="0.81944444"
inkscape:cx="-575.96973"
inkscape:cy="364.74688"
inkscape:window-x="1920"
inkscape:window-y="19"
inkscape:window-maximized="1"
inkscape:current-layer="Layer_3" /><polygon
points="144,46.2 133.2,17.4 154.8,17.4 "
id="polygon3"
transform="matrix(-1,0,0,-1,288,54.034031)"
style="fill:#24d3ee;fill-opacity:1" /><rect
x="135"
y="270"
fill="none"
width="18"
height="18"
id="rect5" /></svg>

After

Width:  |  Height:  |  Size: 1.8 KiB

50
src/FlightMap/Images/compassDottedLine.svg

@ -0,0 +1,50 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<!-- Generator: Adobe Illustrator 19.1.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg
xmlns:dc="http://purl.org/dc/elements/1.1/"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns="http://www.w3.org/2000/svg"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
version="1.1"
id="Layer_2"
x="0px"
y="0px"
viewBox="-161 253 288 288"
enable-background="new -161 253 288 288"
xml:space="preserve"
inkscape:version="0.91 r13725"
sodipodi:docname="compassDottedLine.svg"><metadata
id="metadata131"><rdf:RDF><cc:Work
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /></cc:Work></rdf:RDF></metadata><defs
id="defs129" /><sodipodi:namedview
pagecolor="#ffffff"
bordercolor="#666666"
borderopacity="1"
objecttolerance="10"
gridtolerance="10"
guidetolerance="10"
inkscape:pageopacity="0"
inkscape:pageshadow="2"
inkscape:window-width="958"
inkscape:window-height="1059"
id="namedview127"
showgrid="false"
inkscape:zoom="4.5274476"
inkscape:cx="124.86047"
inkscape:cy="273.06273"
inkscape:window-x="1920"
inkscape:window-y="19"
inkscape:window-maximized="0"
inkscape:current-layer="Layer_2"
inkscape:snap-bbox="true"
inkscape:snap-object-midpoints="true"
inkscape:snap-center="true" /><path
style="fill:#088006;fill-opacity:1;fill-rule:evenodd;stroke:#088006;stroke-width:7.11199999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:3.29999995;stroke-dasharray:14.22399998,7.11199999;stroke-dashoffset:17.99335997;stroke-opacity:1"
d="m -17.131076,320.82151 0.10597,-60.58956"
id="path4263"
inkscape:connector-curvature="0" /></svg>

After

Width:  |  Height:  |  Size: 2.0 KiB

89
src/FlightMap/Widgets/QGCCompassWidget.qml

@ -17,6 +17,7 @@
import QtQuick 2.3 import QtQuick 2.3
import QtGraphicalEffects 1.0 import QtGraphicalEffects 1.0
import QGroundControl 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0 import QGroundControl.Vehicle 1.0
@ -34,6 +35,36 @@ Item {
property real _sizeRatio: ScreenTools.isTinyScreen ? (size / _defaultSize) * 0.5 : size / _defaultSize property real _sizeRatio: ScreenTools.isTinyScreen ? (size / _defaultSize) * 0.5 : size / _defaultSize
property int _fontSize: ScreenTools.defaultFontPointSize * _sizeRatio property int _fontSize: ScreenTools.defaultFontPointSize * _sizeRatio
property real _heading: vehicle ? vehicle.heading.rawValue : 0 property real _heading: vehicle ? vehicle.heading.rawValue : 0
property real _headingToHome: vehicle ? vehicle.headingToHome.rawValue : 0
property real _groundSpeed: vehicle ? vehicle.groundSpeed.rawValue : 0
property real _headingToNextWP: vehicle ? vehicle.headingToNextWP.rawValue : 0
property real _courseOverGround:activeVehicle ? activeVehicle.gps.courseOverGround.rawValue : 0
property bool usedByMultipleVehicleList: false
function isCOGAngleOK(){
if(_groundSpeed < 0.5){
return false
}
else{
return vehicle && _showAdditionalIndicatorsCompass
}
}
function isHeadingHomeOK(){
return vehicle && _showAdditionalIndicatorsCompass && !isNaN(_headingToHome)
}
function isHeadingToNextWPOK(){
return vehicle && _showAdditionalIndicatorsCompass && !isNaN(_headingToNextWP)
}
function isNoseUpLocked(){
return _lockNoseUpCompass
}
readonly property bool _showAdditionalIndicatorsCompass: QGroundControl.settingsManager.flyViewSettings.showAdditionalIndicatorsCompass.value && !usedByMultipleVehicleList
readonly property bool _lockNoseUpCompass: QGroundControl.settingsManager.flyViewSettings.lockNoseUpCompass.value
QGCPalette { id: qgcPal; colorGroupEnabled: enabled } QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
@ -51,6 +82,55 @@ Item {
anchors.fill: parent anchors.fill: parent
visible: false visible: false
Image {
id: cOGPointer
source: isCOGAngleOK() ? "/qmlimages/cOGPointer.svg" : ""
mipmap: true
fillMode: Image.PreserveAspectFit
anchors.fill: parent
sourceSize.height: parent.height
transform: Rotation {
property var _angle:isNoseUpLocked()?_courseOverGround-_heading:_courseOverGround
origin.x: cOGPointer.width / 2
origin.y: cOGPointer.height / 2
angle: _angle
}
}
Image {
id: nextWPPointer
source: isHeadingToNextWPOK() ? "/qmlimages/compassDottedLine.svg":""
mipmap: true
fillMode: Image.PreserveAspectFit
anchors.fill: parent
sourceSize.height: parent.height
transform: Rotation {
property var _angle: isNoseUpLocked()?_headingToNextWP-_heading:_headingToNextWP
origin.x: cOGPointer.width / 2
origin.y: cOGPointer.height / 2
angle: _angle
}
}
Image {
id: homePointer
width: size * 0.1
source: isHeadingHomeOK() ? "/qmlimages/Home.svg" : ""
mipmap: true
fillMode: Image.PreserveAspectFit
anchors.centerIn: parent
sourceSize.width: width
transform: Translate {
property double _angle: isNoseUpLocked()?-_heading+_headingToHome:_headingToHome
x: size/2.3 * Math.sin((_angle)*(3.14/180))
y: - size/2.3 * Math.cos((_angle)*(3.14/180))
}
}
Image { Image {
id: pointer id: pointer
width: size * 0.65 width: size * 0.65
@ -62,10 +142,11 @@ Item {
transform: Rotation { transform: Rotation {
origin.x: pointer.width / 2 origin.x: pointer.width / 2
origin.y: pointer.height / 2 origin.y: pointer.height / 2
angle: _heading angle: isNoseUpLocked()?0:_heading
} }
} }
QGCColoredImage { QGCColoredImage {
id: compassDial id: compassDial
source: "/qmlimages/compassInstrumentDial.svg" source: "/qmlimages/compassInstrumentDial.svg"
@ -74,7 +155,13 @@ Item {
anchors.fill: parent anchors.fill: parent
sourceSize.height: parent.height sourceSize.height: parent.height
color: qgcPal.text color: qgcPal.text
transform: Rotation {
origin.x: compassDial.width / 2
origin.y: compassDial.height / 2
angle: isNoseUpLocked()?-_heading:0
} }
}
Rectangle { Rectangle {
anchors.centerIn: parent anchors.centerIn: parent

2
src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml

@ -19,7 +19,7 @@ import QGroundControl.Palette 1.0
Rectangle { Rectangle {
id: root id: root
width: getPreferredInstrumentWidth() * 0.7 width: getPreferredInstrumentWidth()
height: _outerRadius * 4 + _valuesWidget.height height: _outerRadius * 4 + _valuesWidget.height
radius: _outerRadius radius: _outerRadius
color: qgcPal.window color: qgcPal.window

12
src/Settings/FlyView.SettingsGroup.json

@ -26,6 +26,18 @@
"defaultValue": false "defaultValue": false
}, },
{ {
"name": "showAdditionalIndicatorsCompass",
"shortDescription": "Show additional heading indicators on Compass",
"type": "bool",
"defaultValue": false
},
{
"name": "lockNoseUpCompass",
"shortDescription": "Lock Compass Nose-Up",
"type": "bool",
"defaultValue": false
},
{
"name": "maxGoToLocationDistance", "name": "maxGoToLocationDistance",
"shortDescription": "Maximum distance allowed for Go To Location.", "shortDescription": "Maximum distance allowed for Go To Location.",
"type": "double", "type": "double",

2
src/Settings/FlyViewSettings.cc

@ -21,4 +21,6 @@ DECLARE_SETTINGSFACT(FlyViewSettings, guidedMinimumAltitude)
DECLARE_SETTINGSFACT(FlyViewSettings, guidedMaximumAltitude) DECLARE_SETTINGSFACT(FlyViewSettings, guidedMaximumAltitude)
DECLARE_SETTINGSFACT(FlyViewSettings, showLogReplayStatusBar) DECLARE_SETTINGSFACT(FlyViewSettings, showLogReplayStatusBar)
DECLARE_SETTINGSFACT(FlyViewSettings, alternateInstrumentPanel) DECLARE_SETTINGSFACT(FlyViewSettings, alternateInstrumentPanel)
DECLARE_SETTINGSFACT(FlyViewSettings, showAdditionalIndicatorsCompass)
DECLARE_SETTINGSFACT(FlyViewSettings, lockNoseUpCompass)
DECLARE_SETTINGSFACT(FlyViewSettings, maxGoToLocationDistance) DECLARE_SETTINGSFACT(FlyViewSettings, maxGoToLocationDistance)

2
src/Settings/FlyViewSettings.h

@ -23,5 +23,7 @@ public:
DEFINE_SETTINGFACT(guidedMaximumAltitude) DEFINE_SETTINGFACT(guidedMaximumAltitude)
DEFINE_SETTINGFACT(showLogReplayStatusBar) DEFINE_SETTINGFACT(showLogReplayStatusBar)
DEFINE_SETTINGFACT(alternateInstrumentPanel) DEFINE_SETTINGFACT(alternateInstrumentPanel)
DEFINE_SETTINGFACT(showAdditionalIndicatorsCompass)
DEFINE_SETTINGFACT(lockNoseUpCompass)
DEFINE_SETTINGFACT(maxGoToLocationDistance) DEFINE_SETTINGFACT(maxGoToLocationDistance)
}; };

23
src/Vehicle/Vehicle.cc

@ -73,6 +73,7 @@ const char* Vehicle::_altitudeAMSLFactName = "altitudeAMSL";
const char* Vehicle::_flightDistanceFactName = "flightDistance"; const char* Vehicle::_flightDistanceFactName = "flightDistance";
const char* Vehicle::_flightTimeFactName = "flightTime"; const char* Vehicle::_flightTimeFactName = "flightTime";
const char* Vehicle::_distanceToHomeFactName = "distanceToHome"; const char* Vehicle::_distanceToHomeFactName = "distanceToHome";
const char* Vehicle::_headingToNextWPFactName = "headingToNextWP";
const char* Vehicle::_headingToHomeFactName = "headingToHome"; const char* Vehicle::_headingToHomeFactName = "headingToHome";
const char* Vehicle::_distanceToGCSFactName = "distanceToGCS"; const char* Vehicle::_distanceToGCSFactName = "distanceToGCS";
const char* Vehicle::_hobbsFactName = "hobbs"; const char* Vehicle::_hobbsFactName = "hobbs";
@ -203,6 +204,7 @@ Vehicle::Vehicle(LinkInterface* link,
, _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble) , _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble)
, _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds) , _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds)
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble) , _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _headingToNextWPFact (0, _headingToNextWPFactName, FactMetaData::valueTypeDouble)
, _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble) , _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble)
, _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble) , _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString) , _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
@ -404,6 +406,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble) , _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble)
, _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds) , _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds)
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble) , _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _headingToNextWPFact (0, _headingToNextWPFactName, FactMetaData::valueTypeDouble)
, _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble) , _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble)
, _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble) , _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString) , _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
@ -438,6 +441,7 @@ void Vehicle::_commonInit(void)
connect(this, &Vehicle::homePositionChanged, this, &Vehicle::_updateDistanceHeadingToHome); connect(this, &Vehicle::homePositionChanged, this, &Vehicle::_updateDistanceHeadingToHome);
connect(this, &Vehicle::hobbsMeterChanged, this, &Vehicle::_updateHobbsMeter); connect(this, &Vehicle::hobbsMeterChanged, this, &Vehicle::_updateHobbsMeter);
connect(_toolbox->qgcPositionManager(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateDistanceToGCS); connect(_toolbox->qgcPositionManager(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateDistanceToGCS);
_missionManager = new MissionManager(this); _missionManager = new MissionManager(this);
@ -447,6 +451,7 @@ void Vehicle::_commonInit(void)
connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearTrajectoryPoints); connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearTrajectoryPoints);
connect(_missionManager, &MissionManager::sendComplete, this, &Vehicle::_clearCameraTriggerPoints); connect(_missionManager, &MissionManager::sendComplete, this, &Vehicle::_clearCameraTriggerPoints);
connect(_missionManager, &MissionManager::sendComplete, this, &Vehicle::_clearTrajectoryPoints); connect(_missionManager, &MissionManager::sendComplete, this, &Vehicle::_clearTrajectoryPoints);
connect(_missionManager, &MissionManager::currentIndexChanged, this, &Vehicle::_updateHeadingToNextWP);
_parameterManager = new ParameterManager(this); _parameterManager = new ParameterManager(this);
connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady); connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
@ -481,6 +486,7 @@ void Vehicle::_commonInit(void)
_addFact(&_flightDistanceFact, _flightDistanceFactName); _addFact(&_flightDistanceFact, _flightDistanceFactName);
_addFact(&_flightTimeFact, _flightTimeFactName); _addFact(&_flightTimeFact, _flightTimeFactName);
_addFact(&_distanceToHomeFact, _distanceToHomeFactName); _addFact(&_distanceToHomeFact, _distanceToHomeFactName);
_addFact(&_headingToNextWPFact, _headingToNextWPFactName);
_addFact(&_headingToHomeFact, _headingToHomeFactName); _addFact(&_headingToHomeFact, _headingToHomeFactName);
_addFact(&_distanceToGCSFact, _distanceToGCSFactName); _addFact(&_distanceToGCSFact, _distanceToGCSFactName);
_addFact(&_throttlePctFact, _throttlePctFactName); _addFact(&_throttlePctFact, _throttlePctFactName);
@ -3795,6 +3801,23 @@ void Vehicle::_updateDistanceHeadingToHome(void)
} }
} }
void Vehicle::_updateHeadingToNextWP(void)
{
const int _currentIndex = _missionManager->currentIndex();
MissionItem _currentItem;
QList<MissionItem*> llist = _missionManager->missionItems();
if(llist.size()>_currentIndex && _currentIndex!=-1
&& llist[_currentIndex]->coordinate().longitude()!=0.0
&& coordinate().distanceTo(llist[_currentIndex]->coordinate())>5.0 ){
_headingToNextWPFact.setRawValue(coordinate().azimuthTo(llist[_currentIndex]->coordinate()));
}
else{
_headingToNextWPFact.setRawValue(qQNaN());
}
}
void Vehicle::_updateDistanceToGCS(void) void Vehicle::_updateDistanceToGCS(void)
{ {
QGeoCoordinate gcsPosition = _toolbox->qgcPositionManager()->gcsPosition(); QGeoCoordinate gcsPosition = _toolbox->qgcPositionManager()->gcsPosition();

5
src/Vehicle/Vehicle.h

@ -671,6 +671,7 @@ public:
Q_PROPERTY(Fact* altitudeAMSL READ altitudeAMSL CONSTANT) Q_PROPERTY(Fact* altitudeAMSL READ altitudeAMSL CONSTANT)
Q_PROPERTY(Fact* flightDistance READ flightDistance CONSTANT) Q_PROPERTY(Fact* flightDistance READ flightDistance CONSTANT)
Q_PROPERTY(Fact* distanceToHome READ distanceToHome CONSTANT) Q_PROPERTY(Fact* distanceToHome READ distanceToHome CONSTANT)
Q_PROPERTY(Fact* headingToNextWP READ headingToNextWP CONSTANT)
Q_PROPERTY(Fact* headingToHome READ headingToHome CONSTANT) Q_PROPERTY(Fact* headingToHome READ headingToHome CONSTANT)
Q_PROPERTY(Fact* distanceToGCS READ distanceToGCS CONSTANT) Q_PROPERTY(Fact* distanceToGCS READ distanceToGCS CONSTANT)
Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT) Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT)
@ -973,6 +974,7 @@ public:
Fact* altitudeAMSL (void) { return &_altitudeAMSLFact; } Fact* altitudeAMSL (void) { return &_altitudeAMSLFact; }
Fact* flightDistance (void) { return &_flightDistanceFact; } Fact* flightDistance (void) { return &_flightDistanceFact; }
Fact* distanceToHome (void) { return &_distanceToHomeFact; } Fact* distanceToHome (void) { return &_distanceToHomeFact; }
Fact* headingToNextWP (void) { return &_headingToNextWPFact; }
Fact* headingToHome (void) { return &_headingToHomeFact; } Fact* headingToHome (void) { return &_headingToHomeFact; }
Fact* distanceToGCS (void) { return &_distanceToGCSFact; } Fact* distanceToGCS (void) { return &_distanceToGCSFact; }
Fact* hobbs (void) { return &_hobbsFact; } Fact* hobbs (void) { return &_hobbsFact; }
@ -1246,6 +1248,7 @@ private slots:
void _clearTrajectoryPoints(void); void _clearTrajectoryPoints(void);
void _clearCameraTriggerPoints(void); void _clearCameraTriggerPoints(void);
void _updateDistanceHeadingToHome(void); void _updateDistanceHeadingToHome(void);
void _updateHeadingToNextWP(void);
void _updateDistanceToGCS(void); void _updateDistanceToGCS(void);
void _updateHobbsMeter(void); void _updateHobbsMeter(void);
void _vehicleParamLoaded(bool ready); void _vehicleParamLoaded(bool ready);
@ -1540,6 +1543,7 @@ private:
Fact _flightDistanceFact; Fact _flightDistanceFact;
Fact _flightTimeFact; Fact _flightTimeFact;
Fact _distanceToHomeFact; Fact _distanceToHomeFact;
Fact _headingToNextWPFact;
Fact _headingToHomeFact; Fact _headingToHomeFact;
Fact _distanceToGCSFact; Fact _distanceToGCSFact;
Fact _hobbsFact; Fact _hobbsFact;
@ -1570,6 +1574,7 @@ private:
static const char* _flightDistanceFactName; static const char* _flightDistanceFactName;
static const char* _flightTimeFactName; static const char* _flightTimeFactName;
static const char* _distanceToHomeFactName; static const char* _distanceToHomeFactName;
static const char* _headingToNextWPFactName;
static const char* _headingToHomeFactName; static const char* _headingToHomeFactName;
static const char* _distanceToGCSFactName; static const char* _distanceToGCSFactName;
static const char* _hobbsFactName; static const char* _hobbsFactName;

7
src/Vehicle/VehicleFact.json

@ -105,6 +105,13 @@
"units": "m" "units": "m"
}, },
{ {
"name": "headingToNextWP",
"shortDescription": "Next WP Heading",
"type": "double",
"decimalPlaces": 0,
"units": "deg"
},
{
"name": "flightTime", "name": "flightTime",
"shortDescription": "Flight Time", "shortDescription": "Flight Time",
"type": "elapsedSeconds", "type": "elapsedSeconds",

15
src/ui/preferences/GeneralSettings.qml

@ -482,6 +482,21 @@ Rectangle {
property Fact _alternateInstrumentPanel: QGroundControl.settingsManager.flyViewSettings.alternateInstrumentPanel property Fact _alternateInstrumentPanel: QGroundControl.settingsManager.flyViewSettings.alternateInstrumentPanel
} }
FactCheckBox {
text: qsTr("Show additional heading indicators on Compass")
visible: _showAdditionalIndicatorsCompass.visible
fact: _showAdditionalIndicatorsCompass
property Fact _showAdditionalIndicatorsCompass: QGroundControl.settingsManager.flyViewSettings.showAdditionalIndicatorsCompass
}
FactCheckBox {
text: qsTr("Lock Compass Nose-Up")
visible: _lockNoseUpCompass.visible
fact: _lockNoseUpCompass
property Fact _lockNoseUpCompass: QGroundControl.settingsManager.flyViewSettings.lockNoseUpCompass
}
GridLayout { GridLayout {
columns: 2 columns: 2

Loading…
Cancel
Save