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
bda9e6dc
Unverified
Commit
bda9e6dc
authored
Mar 23, 2018
by
Don Gagne
Committed by
GitHub
Mar 23, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6250 from DonLakeFlyer/Fixes
Pile 'o bug fixes
parents
1513ec55
908fe5db
Changes
16
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
16 changed files
with
31 additions
and
147 deletions
+31
-147
qgroundcontrol.pro
qgroundcontrol.pro
+0
-1
FlightMap.qml
src/FlightMap/FlightMap.qml
+0
-1
MissionCommandList.h
src/MissionManager/MissionCommandList.h
+0
-1
MissionController.cc
src/MissionManager/MissionController.cc
+10
-10
MissionController.h
src/MissionManager/MissionController.h
+0
-1
MissionControllerTest.cc
src/MissionManager/MissionControllerTest.cc
+1
-1
MissionItem.h
src/MissionManager/MissionItem.h
+0
-1
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+6
-6
SimpleMissionItem.h
src/MissionManager/SimpleMissionItem.h
+3
-3
SimpleMissionItemTest.cc
src/MissionManager/SimpleMissionItemTest.cc
+2
-2
VisualMissionItem.h
src/MissionManager/VisualMissionItem.h
+0
-1
PlanView.qml
src/PlanView/PlanView.qml
+0
-1
QGCApplication.cc
src/QGCApplication.cc
+0
-7
MavlinkQmlSingleton.h
src/QmlControls/MavlinkQmlSingleton.h
+0
-109
ParameterEditor.qml
src/QmlControls/ParameterEditor.qml
+3
-1
Vehicle.cc
src/Vehicle/Vehicle.cc
+6
-1
No files found.
qgroundcontrol.pro
View file @
bda9e6dc
...
...
@@ -568,7 +568,6 @@ HEADERS += \
src
/
QmlControls
/
AppMessages
.
h
\
src
/
QmlControls
/
CoordinateVector
.
h
\
src
/
QmlControls
/
EditPositionDialogController
.
h
\
src
/
QmlControls
/
MavlinkQmlSingleton
.
h
\
src
/
QmlControls
/
ParameterEditorController
.
h
\
src
/
QmlControls
/
QGCFileDialogController
.
h
\
src
/
QmlControls
/
QGCImageProvider
.
h
\
...
...
src/FlightMap/FlightMap.qml
View file @
bda9e6dc
...
...
@@ -19,7 +19,6 @@ import QGroundControl.FlightMap 1.0
import
QGroundControl
.
ScreenTools
1.0
import
QGroundControl
.
MultiVehicleManager
1.0
import
QGroundControl
.
Vehicle
1.0
import
QGroundControl
.
Mavlink
1.0
import
QGroundControl
.
QGCPositionManager
1.0
Map
{
...
...
src/MissionManager/MissionCommandList.h
View file @
bda9e6dc
...
...
@@ -14,7 +14,6 @@
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
#include "MavlinkQmlSingleton.h"
#include <QObject>
#include <QString>
...
...
src/MissionManager/MissionController.cc
View file @
bda9e6dc
...
...
@@ -335,10 +335,10 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
SimpleMissionItem
*
newItem
=
new
SimpleMissionItem
(
_controllerVehicle
,
this
);
newItem
->
setSequenceNumber
(
sequenceNumber
);
newItem
->
setCoordinate
(
coordinate
);
newItem
->
setCommand
(
M
avlinkQmlSingleton
::
M
AV_CMD_NAV_WAYPOINT
);
newItem
->
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
_initVisualItem
(
newItem
);
if
(
_visualItems
->
count
()
==
1
)
{
M
avlinkQmlSingleton
::
Qml_MAV_CMD
takeoffCmd
=
_controllerVehicle
->
vtol
()
?
MavlinkQmlSingleton
::
MAV_CMD_NAV_VTOL_TAKEOFF
:
MavlinkQmlSingleton
::
MAV_CMD_NAV_TAKEOFF
;
M
AV_CMD
takeoffCmd
=
_controllerVehicle
->
vtol
()
?
MAV_CMD_NAV_VTOL_TAKEOFF
:
MAV_CMD_NAV_TAKEOFF
;
if
(
_controllerVehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
((
MAV_CMD
)
takeoffCmd
))
{
newItem
->
setCommand
(
takeoffCmd
);
}
...
...
@@ -366,7 +366,7 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
int
sequenceNumber
=
_nextSequenceNumber
();
SimpleMissionItem
*
newItem
=
new
SimpleMissionItem
(
_controllerVehicle
,
this
);
newItem
->
setSequenceNumber
(
sequenceNumber
);
newItem
->
setCommand
((
M
avlinkQmlSingleton
::
Qml_M
AV_CMD
)(
_controllerVehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
((
MAV_CMD
)
MAV_CMD_DO_SET_ROI_LOCATION
)
?
newItem
->
setCommand
((
MAV_CMD
)(
_controllerVehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
((
MAV_CMD
)
MAV_CMD_DO_SET_ROI_LOCATION
)
?
MAV_CMD_DO_SET_ROI_LOCATION
:
MAV_CMD_DO_SET_ROI
));
_initVisualItem
(
newItem
);
...
...
@@ -840,7 +840,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
// Update sequence numbers in DO_JUMP commands to take into account added home position in index 0
for
(
int
i
=
1
;
i
<
visualItems
->
count
();
i
++
)
{
SimpleMissionItem
*
item
=
qobject_cast
<
SimpleMissionItem
*>
(
visualItems
->
get
(
i
));
if
(
item
&&
item
->
command
()
==
M
avlinkQmlSingleton
::
M
AV_CMD_DO_JUMP
)
{
if
(
item
&&
item
->
command
()
==
MAV_CMD_DO_JUMP
)
{
item
->
missionItem
().
setParam1
((
int
)
item
->
missionItem
().
param1
()
+
1
);
}
}
...
...
@@ -1297,7 +1297,7 @@ void MissionController::_recalcMissionFlightStatus()
}
// Link back to home if first item is takeoff and we have home position
if
(
firstCoordinateItem
&&
simpleItem
&&
(
simpleItem
->
command
()
==
M
avlinkQmlSingleton
::
MAV_CMD_NAV_TAKEOFF
||
simpleItem
->
command
()
==
MavlinkQmlSingleton
::
MAV_CMD_NAV_VTOL_TAKEOFF
))
{
if
(
firstCoordinateItem
&&
simpleItem
&&
(
simpleItem
->
command
()
==
M
AV_CMD_NAV_TAKEOFF
||
simpleItem
->
command
()
==
MAV_CMD_NAV_VTOL_TAKEOFF
))
{
if
(
showHomePosition
)
{
linkStartToHome
=
true
;
if
(
_controllerVehicle
->
multiRotor
()
||
_controllerVehicle
->
vtol
())
{
...
...
@@ -1313,19 +1313,19 @@ void MissionController::_recalcMissionFlightStatus()
// Update VTOL state
if
(
simpleItem
&&
_controllerVehicle
->
vtol
())
{
switch
(
simpleItem
->
command
())
{
case
M
avlinkQmlSingleton
:
:
M
AV_CMD_NAV_TAKEOFF
:
case
MAV_CMD_NAV_TAKEOFF
:
vtolInHover
=
false
;
break
;
case
M
avlinkQmlSingleton
:
:
M
AV_CMD_NAV_VTOL_TAKEOFF
:
case
MAV_CMD_NAV_VTOL_TAKEOFF
:
vtolInHover
=
true
;
break
;
case
M
avlinkQmlSingleton
:
:
M
AV_CMD_NAV_LAND
:
case
MAV_CMD_NAV_LAND
:
vtolInHover
=
false
;
break
;
case
M
avlinkQmlSingleton
:
:
M
AV_CMD_NAV_VTOL_LAND
:
case
MAV_CMD_NAV_VTOL_LAND
:
vtolInHover
=
true
;
break
;
case
M
avlinkQmlSingleton
:
:
M
AV_CMD_DO_VTOL_TRANSITION
:
case
MAV_CMD_DO_VTOL_TRANSITION
:
{
int
transitionState
=
simpleItem
->
missionItem
().
param1
();
if
(
transitionState
==
MAV_VTOL_STATE_TRANSITION_TO_MC
)
{
...
...
src/MissionManager/MissionController.h
View file @
bda9e6dc
...
...
@@ -15,7 +15,6 @@
#include "QmlObjectListModel.h"
#include "Vehicle.h"
#include "QGCLoggingCategory.h"
#include "MavlinkQmlSingleton.h"
#include <QHash>
...
...
src/MissionManager/MissionControllerTest.cc
View file @
bda9e6dc
...
...
@@ -132,7 +132,7 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
QVERIFY
(
settingsItem
);
QVERIFY
(
simpleItem
);
QCOMPARE
(
simpleItem
->
command
(),
MavlinkQmlSingleton
::
MAV_CMD_NAV_TAKEOFF
);
QCOMPARE
(
(
MAV_CMD
)
simpleItem
->
command
(),
MAV_CMD_NAV_TAKEOFF
);
QCOMPARE
(
simpleItem
->
childItems
()
->
count
(),
0
);
// If the first item added specifies a coordinate, then planned home position will be set
...
...
src/MissionManager/MissionItem.h
View file @
bda9e6dc
...
...
@@ -20,7 +20,6 @@
#include "QGCMAVLink.h"
#include "QGC.h"
#include "MavlinkQmlSingleton.h"
#include "QmlObjectListModel.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
bda9e6dc
...
...
@@ -392,15 +392,15 @@ QString SimpleMissionItem::abbreviation() const
return
tr
(
"H"
);
switch
(
command
())
{
case
M
avlinkQmlSingleton
:
:
M
AV_CMD_NAV_TAKEOFF
:
case
MAV_CMD_NAV_TAKEOFF
:
return
tr
(
"Takeoff"
);
case
M
avlinkQmlSingleton
:
:
M
AV_CMD_NAV_LAND
:
case
MAV_CMD_NAV_LAND
:
return
tr
(
"Land"
);
case
M
avlinkQmlSingleton
:
:
M
AV_CMD_NAV_VTOL_TAKEOFF
:
case
MAV_CMD_NAV_VTOL_TAKEOFF
:
return
tr
(
"VTOL Takeoff"
);
case
M
avlinkQmlSingleton
:
:
M
AV_CMD_NAV_VTOL_LAND
:
case
MAV_CMD_NAV_VTOL_LAND
:
return
tr
(
"VTOL Land"
);
case
M
avlinkQmlSingleton
:
:
M
AV_CMD_DO_SET_ROI
:
case
MAV_CMD_DO_SET_ROI
:
return
tr
(
"ROI"
);
default:
return
QString
();
...
...
@@ -750,7 +750,7 @@ QString SimpleMissionItem::category(void) const
return
_commandTree
->
getUIInfo
(
_vehicle
,
(
MAV_CMD
)
command
())
->
category
();
}
void
SimpleMissionItem
::
setCommand
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
)
void
SimpleMissionItem
::
setCommand
(
int
command
)
{
if
((
MAV_CMD
)
command
!=
_missionItem
.
command
())
{
_missionItem
.
setCommand
((
MAV_CMD
)
command
);
...
...
src/MissionManager/SimpleMissionItem.h
View file @
bda9e6dc
...
...
@@ -44,7 +44,7 @@ public:
Q_PROPERTY
(
Fact
*
altitude
READ
altitude
CONSTANT
)
///< Altitude as specified by altitudeMode. Not necessarily true mission item altitude
Q_PROPERTY
(
AltitudeMode
altitudeMode
READ
altitudeMode
WRITE
setAltitudeMode
NOTIFY
altitudeModeChanged
)
Q_PROPERTY
(
Fact
*
amslAltAboveTerrain
READ
amslAltAboveTerrain
CONSTANT
)
///< Actual AMSL altitude for item if altitudeMode == AltitudeAboveTerrain
Q_PROPERTY
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
READ
command
WRITE
setCommand
NOTIFY
commandChanged
)
Q_PROPERTY
(
int
command
READ
command
WRITE
setCommand
NOTIFY
commandChanged
)
/// Optional sections
Q_PROPERTY
(
QObject
*
speedSection
READ
speedSection
NOTIFY
speedSectionChanged
)
...
...
@@ -65,7 +65,7 @@ public:
// Property accesors
QString
category
(
void
)
const
;
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
(
void
)
const
{
return
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
)
_missionItem
.
_commandFact
.
cookedValue
().
toInt
();
}
int
command
(
void
)
const
{
return
_missionItem
.
_commandFact
.
cookedValue
().
toInt
();
}
bool
friendlyEditAllowed
(
void
)
const
;
bool
rawEdit
(
void
)
const
;
bool
specifiesAltitude
(
void
)
const
;
...
...
@@ -85,7 +85,7 @@ public:
void
setCommandByIndex
(
int
index
);
void
setCommand
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
);
void
setCommand
(
int
command
);
void
setAltDifference
(
double
altDifference
);
void
setAltPercent
(
double
altPercent
);
...
...
src/MissionManager/SimpleMissionItemTest.cc
View file @
bda9e6dc
...
...
@@ -236,11 +236,11 @@ void SimpleMissionItemTest::_testSignals(void)
// dirtyChanged
// coordinateChanged - since altitude will be set back to default
_simpleItem
->
setCommand
(
M
avlinkQmlSingleton
::
M
AV_CMD_NAV_WAYPOINT
);
_simpleItem
->
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
QVERIFY
(
_spyVisualItem
->
checkNoSignals
());
QVERIFY
(
_spySimpleItem
->
checkNoSignals
());
_simpleItem
->
setCommand
(
M
avlinkQmlSingleton
::
M
AV_CMD_NAV_LOITER_TIME
);
_simpleItem
->
setCommand
(
MAV_CMD_NAV_LOITER_TIME
);
QVERIFY
(
_spySimpleItem
->
checkSignalsByMask
(
commandChangedMask
));
QVERIFY
(
_spyVisualItem
->
checkSignalsByMask
(
commandNameChangedMask
|
dirtyChangedMask
|
coordinateChangedMask
));
}
...
...
src/MissionManager/VisualMissionItem.h
View file @
bda9e6dc
...
...
@@ -18,7 +18,6 @@
#include "QGCMAVLink.h"
#include "QGC.h"
#include "MavlinkQmlSingleton.h"
#include "QmlObjectListModel.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
...
...
src/PlanView/PlanView.qml
View file @
bda9e6dc
...
...
@@ -23,7 +23,6 @@ import QGroundControl.Controls 1.0
import
QGroundControl
.
FactSystem
1.0
import
QGroundControl
.
FactControls
1.0
import
QGroundControl
.
Palette
1.0
import
QGroundControl
.
Mavlink
1.0
import
QGroundControl
.
Controllers
1.0
/// Mission Editor
...
...
src/QGCApplication.cc
View file @
bda9e6dc
...
...
@@ -57,7 +57,6 @@
#include "FirmwarePluginManager.h"
#include "MultiVehicleManager.h"
#include "Vehicle.h"
#include "MavlinkQmlSingleton.h"
#include "JoystickConfigController.h"
#include "JoystickManager.h"
#include "QmlObjectListModel.h"
...
...
@@ -130,11 +129,6 @@ static QObject* screenToolsControllerSingletonFactory(QQmlEngine*, QJSEngine*)
return
screenToolsController
;
}
static
QObject
*
mavlinkQmlSingletonFactory
(
QQmlEngine
*
,
QJSEngine
*
)
{
return
new
MavlinkQmlSingleton
;
}
static
QObject
*
qgroundcontrolQmlGlobalSingletonFactory
(
QQmlEngine
*
,
QJSEngine
*
)
{
// We create this object as a QGCTool even though it isn't in the toolbox
...
...
@@ -404,7 +398,6 @@ void QGCApplication::_initCommon(void)
// Register Qml Singletons
qmlRegisterSingletonType
<
QGroundControlQmlGlobal
>
(
"QGroundControl"
,
1
,
0
,
"QGroundControl"
,
qgroundcontrolQmlGlobalSingletonFactory
);
qmlRegisterSingletonType
<
ScreenToolsController
>
(
"QGroundControl.ScreenToolsController"
,
1
,
0
,
"ScreenToolsController"
,
screenToolsControllerSingletonFactory
);
qmlRegisterSingletonType
<
MavlinkQmlSingleton
>
(
"QGroundControl.Mavlink"
,
1
,
0
,
"Mavlink"
,
mavlinkQmlSingletonFactory
);
}
bool
QGCApplication
::
_initForNormalAppBoot
(
void
)
...
...
src/QmlControls/MavlinkQmlSingleton.h
deleted
100644 → 0
View file @
1513ec55
This diff is collapsed.
Click to expand it.
src/QmlControls/ParameterEditor.qml
View file @
bda9e6dc
...
...
@@ -32,6 +32,7 @@ QGCView {
property
bool
_searchFilter
:
searchText
.
text
.
trim
()
!=
""
///< true: showing results of search
property
var
_searchResults
///< List of parameter names from search results
property
bool
_showRCToParam
:
!
ScreenTools
.
isMobile
&&
QGroundControl
.
multiVehicleManager
.
activeVehicle
.
px4Firmware
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
ParameterEditorController
{
id
:
controller
;
...
...
@@ -104,6 +105,7 @@ QGCView {
}
MenuItem
{
text
:
qsTr
(
"
Reset all to defaults
"
)
visible
:
!
_activeVehicle
.
apmFirmware
onTriggered
:
showDialog
(
resetToDefaultConfirmComponent
,
qsTr
(
"
Reset All
"
),
qgcView
.
showDialogDefaultWidth
,
StandardButton
.
Cancel
|
StandardButton
.
Reset
)
}
MenuSeparator
{
}
...
...
@@ -334,7 +336,7 @@ QGCView {
QGCViewDialog
{
function
accept
()
{
QGroundControl
.
multiVehicleManager
.
activeVehicle
.
rebootVehicle
()
_
activeVehicle
.
rebootVehicle
()
hideDialog
()
}
...
...
src/Vehicle/Vehicle.cc
View file @
bda9e6dc
...
...
@@ -1139,7 +1139,12 @@ void Vehicle::_handleWind(mavlink_message_t& message)
mavlink_wind_t
wind
;
mavlink_msg_wind_decode
(
&
message
,
&
wind
);
_windFactGroup
.
direction
()
->
setRawValue
(
wind
.
direction
);
// We don't want negative wind angles
float
direction
=
wind
.
direction
;
if
(
direction
<
0
)
{
direction
+=
360
;
}
_windFactGroup
.
direction
()
->
setRawValue
(
direction
);
_windFactGroup
.
speed
()
->
setRawValue
(
wind
.
speed
);
_windFactGroup
.
verticalSpeed
()
->
setRawValue
(
wind
.
speed_z
);
}
...
...
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