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
343e5910
Commit
343e5910
authored
Aug 11, 2019
by
murata
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
MissionManager: Change NULL or 0 to nullptr
parent
0de1d960
Changes
42
Hide whitespace changes
Inline
Side-by-side
Showing
42 changed files
with
106 additions
and
106 deletions
+106
-106
CameraCalc.h
src/MissionManager/CameraCalc.h
+1
-1
CameraCalcTest.cc
src/MissionManager/CameraCalcTest.cc
+1
-1
CameraSection.cc
src/MissionManager/CameraSection.cc
+1
-1
CameraSection.h
src/MissionManager/CameraSection.h
+1
-1
CameraSectionTest.cc
src/MissionManager/CameraSectionTest.cc
+20
-20
CameraSpec.h
src/MissionManager/CameraSpec.h
+1
-1
CorridorScanComplexItem.cc
src/MissionManager/CorridorScanComplexItem.cc
+1
-1
CorridorScanComplexItemTest.cc
src/MissionManager/CorridorScanComplexItemTest.cc
+1
-1
MissionCommandList.h
src/MissionManager/MissionCommandList.h
+1
-1
MissionCommandTreeTest.cc
src/MissionManager/MissionCommandTreeTest.cc
+8
-8
MissionCommandUIInfo.h
src/MissionManager/MissionCommandUIInfo.h
+4
-4
MissionController.cc
src/MissionManager/MissionController.cc
+4
-4
MissionController.h
src/MissionManager/MissionController.h
+1
-1
MissionControllerManagerTest.cc
src/MissionManager/MissionControllerManagerTest.cc
+1
-1
MissionControllerTest.cc
src/MissionManager/MissionControllerTest.cc
+6
-6
MissionItem.h
src/MissionManager/MissionItem.h
+3
-3
MissionItemTest.cc
src/MissionManager/MissionItemTest.cc
+3
-3
MissionManagerTest.cc
src/MissionManager/MissionManagerTest.cc
+1
-1
MissionSettingsItem.cc
src/MissionManager/MissionSettingsItem.cc
+2
-2
MissionSettingsTest.cc
src/MissionManager/MissionSettingsTest.cc
+1
-1
PlanElementController.h
src/MissionManager/PlanElementController.h
+1
-1
PlanManager.cc
src/MissionManager/PlanManager.cc
+2
-2
PlanMasterController.h
src/MissionManager/PlanMasterController.h
+1
-1
PlanMasterControllerTest.cc
src/MissionManager/PlanMasterControllerTest.cc
+2
-2
QGCFenceCircle.h
src/MissionManager/QGCFenceCircle.h
+3
-3
QGCFencePolygon.h
src/MissionManager/QGCFencePolygon.h
+2
-2
QGCMapPolyline.h
src/MissionManager/QGCMapPolyline.h
+2
-2
RallyPoint.cc
src/MissionManager/RallyPoint.cc
+1
-1
RallyPoint.h
src/MissionManager/RallyPoint.h
+2
-2
RallyPointController.cc
src/MissionManager/RallyPointController.cc
+6
-6
RallyPointController.h
src/MissionManager/RallyPointController.h
+1
-1
Section.h
src/MissionManager/Section.h
+1
-1
SectionTest.cc
src/MissionManager/SectionTest.cc
+2
-2
SpeedSection.cc
src/MissionManager/SpeedSection.cc
+1
-1
SpeedSection.h
src/MissionManager/SpeedSection.h
+1
-1
SpeedSectionTest.cc
src/MissionManager/SpeedSectionTest.cc
+6
-6
SurveyComplexItemTest.cc
src/MissionManager/SurveyComplexItemTest.cc
+1
-1
TransectStyleComplexItemTest.cc
src/MissionManager/TransectStyleComplexItemTest.cc
+1
-1
TransectStyleComplexItemTest.h
src/MissionManager/TransectStyleComplexItemTest.h
+1
-1
VisualMissionItemTest.cc
src/MissionManager/VisualMissionItemTest.cc
+2
-2
PositionManager.cpp
src/PositionManager/PositionManager.cpp
+4
-4
SimulatedPosition.cc
src/PositionManager/SimulatedPosition.cc
+1
-1
No files found.
src/MissionManager/CameraCalc.h
View file @
343e5910
...
@@ -19,7 +19,7 @@ class CameraCalc : public CameraSpec
...
@@ -19,7 +19,7 @@ class CameraCalc : public CameraSpec
Q_OBJECT
Q_OBJECT
public:
public:
CameraCalc
(
Vehicle
*
vehicle
,
const
QString
&
settingsGroup
,
QObject
*
parent
=
NULL
);
CameraCalc
(
Vehicle
*
vehicle
,
const
QString
&
settingsGroup
,
QObject
*
parent
=
nullptr
);
Q_PROPERTY
(
QString
customCameraName
READ
customCameraName
CONSTANT
)
///< Camera name for custom camera setting
Q_PROPERTY
(
QString
customCameraName
READ
customCameraName
CONSTANT
)
///< Camera name for custom camera setting
Q_PROPERTY
(
QString
manualCameraName
READ
manualCameraName
CONSTANT
)
///< Camera name for manual camera setting
Q_PROPERTY
(
QString
manualCameraName
READ
manualCameraName
CONSTANT
)
///< Camera name for manual camera setting
...
...
src/MissionManager/CameraCalcTest.cc
View file @
343e5910
...
@@ -11,7 +11,7 @@
...
@@ -11,7 +11,7 @@
#include "QGCApplication.h"
#include "QGCApplication.h"
CameraCalcTest
::
CameraCalcTest
(
void
)
CameraCalcTest
::
CameraCalcTest
(
void
)
:
_offlineVehicle
(
NULL
)
:
_offlineVehicle
(
nullptr
)
{
{
}
}
...
...
src/MissionManager/CameraSection.cc
View file @
343e5910
...
@@ -147,7 +147,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
...
@@ -147,7 +147,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
}
}
if
(
_cameraActionFact
.
rawValue
().
toInt
()
!=
CameraActionNone
)
{
if
(
_cameraActionFact
.
rawValue
().
toInt
()
!=
CameraActionNone
)
{
MissionItem
*
item
=
NULL
;
MissionItem
*
item
=
nullptr
;
switch
(
_cameraActionFact
.
rawValue
().
toInt
())
{
switch
(
_cameraActionFact
.
rawValue
().
toInt
())
{
case
TakePhotosIntervalTime
:
case
TakePhotosIntervalTime
:
...
...
src/MissionManager/CameraSection.h
View file @
343e5910
...
@@ -21,7 +21,7 @@ class CameraSection : public Section
...
@@ -21,7 +21,7 @@ class CameraSection : public Section
Q_OBJECT
Q_OBJECT
public:
public:
CameraSection
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
CameraSection
(
Vehicle
*
vehicle
,
QObject
*
parent
=
nullptr
);
// These enum values must match the json meta data
// These enum values must match the json meta data
...
...
src/MissionManager/CameraSectionTest.cc
View file @
343e5910
...
@@ -13,16 +13,16 @@
...
@@ -13,16 +13,16 @@
#include "MissionCommandUIInfo.h"
#include "MissionCommandUIInfo.h"
CameraSectionTest
::
CameraSectionTest
(
void
)
CameraSectionTest
::
CameraSectionTest
(
void
)
:
_spyCamera
(
NULL
)
:
_spyCamera
(
nullptr
)
,
_spySection
(
NULL
)
,
_spySection
(
nullptr
)
,
_cameraSection
(
NULL
)
,
_cameraSection
(
nullptr
)
,
_validGimbalItem
(
NULL
)
,
_validGimbalItem
(
nullptr
)
,
_validDistanceItem
(
NULL
)
,
_validDistanceItem
(
nullptr
)
,
_validTimeItem
(
NULL
)
,
_validTimeItem
(
nullptr
)
,
_validStartVideoItem
(
NULL
)
,
_validStartVideoItem
(
nullptr
)
,
_validCameraPhotoModeItem
(
NULL
)
,
_validCameraPhotoModeItem
(
nullptr
)
,
_validCameraVideoModeItem
(
NULL
)
,
_validCameraVideoModeItem
(
nullptr
)
,
_validCameraSurveyPhotoModeItem
(
NULL
)
,
_validCameraSurveyPhotoModeItem
(
nullptr
)
{
{
}
}
...
@@ -143,7 +143,7 @@ void CameraSectionTest::cleanup(void)
...
@@ -143,7 +143,7 @@ void CameraSectionTest::cleanup(void)
void
CameraSectionTest
::
_createSpy
(
CameraSection
*
cameraSection
,
MultiSignalSpy
**
cameraSpy
)
void
CameraSectionTest
::
_createSpy
(
CameraSection
*
cameraSection
,
MultiSignalSpy
**
cameraSpy
)
{
{
*
cameraSpy
=
NULL
;
*
cameraSpy
=
nullptr
;
MultiSignalSpy
*
spy
=
new
MultiSignalSpy
();
MultiSignalSpy
*
spy
=
new
MultiSignalSpy
();
QCOMPARE
(
spy
->
init
(
cameraSection
,
rgCameraSignals
,
cCameraSignals
),
true
);
QCOMPARE
(
spy
->
init
(
cameraSection
,
rgCameraSignals
,
cCameraSignals
),
true
);
*
cameraSpy
=
spy
;
*
cameraSpy
=
spy
;
...
@@ -618,7 +618,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
...
@@ -618,7 +618,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
// Gimbal command but incorrect settings
// Gimbal command but incorrect settings
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validGimbalItem
->
missionItem
(),
NULL
);
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validGimbalItem
->
missionItem
(),
nullptr
);
invalidSimpleItem
.
missionItem
().
setParam2
(
10
);
// roll is not supported
invalidSimpleItem
.
missionItem
().
setParam2
(
10
);
// roll is not supported
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
@@ -708,7 +708,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
...
@@ -708,7 +708,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
*/
*/
// Mode command but incorrect settings
// Mode command but incorrect settings
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validCameraPhotoModeItem
->
missionItem
(),
NULL
);
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validCameraPhotoModeItem
->
missionItem
(),
nullptr
);
invalidSimpleItem
.
missionItem
().
setParam3
(
1
);
// Param3 should be NaN
invalidSimpleItem
.
missionItem
().
setParam3
(
1
);
// Param3 should be NaN
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
@@ -747,7 +747,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
...
@@ -747,7 +747,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
// Image start command but incorrect settings
// Image start command but incorrect settings
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validTimeItem
->
missionItem
(),
NULL
);
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validTimeItem
->
missionItem
(),
nullptr
);
invalidSimpleItem
.
missionItem
().
setParam3
(
10
);
// must be 0 for unlimited
invalidSimpleItem
.
missionItem
().
setParam3
(
10
);
// must be 0 for unlimited
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
@@ -788,7 +788,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
...
@@ -788,7 +788,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
// Trigger distance command but incorrect settings
// Trigger distance command but incorrect settings
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validDistanceItem
->
missionItem
(),
NULL
);
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validDistanceItem
->
missionItem
(),
nullptr
);
invalidSimpleItem
.
missionItem
().
setParam1
(
-
1
);
// must be >= 0
invalidSimpleItem
.
missionItem
().
setParam1
(
-
1
);
// must be >= 0
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
@@ -873,7 +873,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
...
@@ -873,7 +873,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
// Start Video command but incorrect settings
// Start Video command but incorrect settings
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validStartVideoItem
->
missionItem
(),
NULL
);
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validStartVideoItem
->
missionItem
(),
nullptr
);
invalidSimpleItem
.
missionItem
().
setParam1
(
10
);
// Reserved (must be 0)
invalidSimpleItem
.
missionItem
().
setParam1
(
10
);
// Reserved (must be 0)
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
@@ -909,7 +909,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
...
@@ -909,7 +909,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
// Trigger distance command but incorrect settings
// Trigger distance command but incorrect settings
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validStopVideoItem
->
missionItem
(),
NULL
);
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validStopVideoItem
->
missionItem
(),
nullptr
);
invalidSimpleItem
.
missionItem
().
setParam1
(
10
);
// must be 0
invalidSimpleItem
.
missionItem
().
setParam1
(
10
);
// must be 0
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
@@ -949,8 +949,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void)
...
@@ -949,8 +949,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void)
// Out of order commands
// Out of order commands
SimpleMissionItem
validStopDistanceItem
(
_offlineVehicle
,
false
/* flyView */
,
NULL
);
SimpleMissionItem
validStopDistanceItem
(
_offlineVehicle
,
false
/* flyView */
,
nullptr
);
SimpleMissionItem
validStopTimeItem
(
_offlineVehicle
,
false
/* flyView */
,
NULL
);
SimpleMissionItem
validStopTimeItem
(
_offlineVehicle
,
false
/* flyView */
,
nullptr
);
validStopDistanceItem
.
missionItem
()
=
_validStopDistanceItem
->
missionItem
();
validStopDistanceItem
.
missionItem
()
=
_validStopDistanceItem
->
missionItem
();
validStopTimeItem
.
missionItem
()
=
_validStopTimeItem
->
missionItem
();
validStopTimeItem
.
missionItem
()
=
_validStopTimeItem
->
missionItem
();
visualItems
.
append
(
&
validStopTimeItem
);
visualItems
.
append
(
&
validStopTimeItem
);
...
@@ -990,7 +990,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
...
@@ -990,7 +990,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
// Take Photo command but incorrect settings
// Take Photo command but incorrect settings
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validTimeItem
->
missionItem
(),
NULL
);
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
false
/* flyView */
,
_validTimeItem
->
missionItem
(),
nullptr
);
invalidSimpleItem
.
missionItem
().
setParam3
(
10
);
// must be 1 for single photo
invalidSimpleItem
.
missionItem
().
setParam3
(
10
);
// must be 1 for single photo
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
...
src/MissionManager/CameraSpec.h
View file @
343e5910
...
@@ -16,7 +16,7 @@ class CameraSpec : public QObject
...
@@ -16,7 +16,7 @@ class CameraSpec : public QObject
Q_OBJECT
Q_OBJECT
public:
public:
CameraSpec
(
const
QString
&
settingsGroup
,
QObject
*
parent
=
NULL
);
CameraSpec
(
const
QString
&
settingsGroup
,
QObject
*
parent
=
nullptr
);
const
CameraSpec
&
operator
=
(
const
CameraSpec
&
other
);
const
CameraSpec
&
operator
=
(
const
CameraSpec
&
other
);
...
...
src/MissionManager/CorridorScanComplexItem.cc
View file @
343e5910
...
@@ -335,7 +335,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
...
@@ -335,7 +335,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
if
(
_loadedMissionItemsParent
)
{
if
(
_loadedMissionItemsParent
)
{
_loadedMissionItems
.
clear
();
_loadedMissionItems
.
clear
();
_loadedMissionItemsParent
->
deleteLater
();
_loadedMissionItemsParent
->
deleteLater
();
_loadedMissionItemsParent
=
NULL
;
_loadedMissionItemsParent
=
nullptr
;
}
}
_transects
.
clear
();
_transects
.
clear
();
...
...
src/MissionManager/CorridorScanComplexItemTest.cc
View file @
343e5910
...
@@ -11,7 +11,7 @@
...
@@ -11,7 +11,7 @@
#include "QGCApplication.h"
#include "QGCApplication.h"
CorridorScanComplexItemTest
::
CorridorScanComplexItemTest
(
void
)
CorridorScanComplexItemTest
::
CorridorScanComplexItemTest
(
void
)
:
_offlineVehicle
(
NULL
)
:
_offlineVehicle
(
nullptr
)
{
{
_linePoints
<<
QGeoCoordinate
(
47.633550640000003
,
-
122.08982199
)
_linePoints
<<
QGeoCoordinate
(
47.633550640000003
,
-
122.08982199
)
<<
QGeoCoordinate
(
47.634129020000003
,
-
122.08887249
)
<<
QGeoCoordinate
(
47.634129020000003
,
-
122.08887249
)
...
...
src/MissionManager/MissionCommandList.h
View file @
343e5910
...
@@ -30,7 +30,7 @@ class MissionCommandList : public QObject
...
@@ -30,7 +30,7 @@ class MissionCommandList : public QObject
public:
public:
/// @param jsonFilename Json file which contains commands
/// @param jsonFilename Json file which contains commands
/// @param baseCommandList true: bottomost level of mission command hierarchy (partial not allowed), false: mid-level of command hierarchy
/// @param baseCommandList true: bottomost level of mission command hierarchy (partial not allowed), false: mid-level of command hierarchy
MissionCommandList
(
const
QString
&
jsonFilename
,
bool
baseCommandList
,
QObject
*
parent
=
NULL
);
MissionCommandList
(
const
QString
&
jsonFilename
,
bool
baseCommandList
,
QObject
*
parent
=
nullptr
);
/// Returns list of categories in this list
/// Returns list of categories in this list
QStringList
&
categories
(
void
)
{
return
_categories
;
}
QStringList
&
categories
(
void
)
{
return
_categories
;
}
...
...
src/MissionManager/MissionCommandTreeTest.cc
View file @
343e5910
...
@@ -59,7 +59,7 @@ void MissionCommandTreeTest::_checkFullInfoMap(const MissionCommandUIInfo* uiInf
...
@@ -59,7 +59,7 @@ void MissionCommandTreeTest::_checkFullInfoMap(const MissionCommandUIInfo* uiInf
// Verifies that values match settings for base tree
// Verifies that values match settings for base tree
void
MissionCommandTreeTest
::
_checkBaseValues
(
const
MissionCommandUIInfo
*
uiInfo
,
int
command
)
void
MissionCommandTreeTest
::
_checkBaseValues
(
const
MissionCommandUIInfo
*
uiInfo
,
int
command
)
{
{
QVERIFY
(
uiInfo
!=
NULL
);
QVERIFY
(
uiInfo
!=
nullptr
);
_checkFullInfoMap
(
uiInfo
);
_checkFullInfoMap
(
uiInfo
);
QCOMPARE
(
uiInfo
->
command
(),
(
MAV_CMD
)
command
);
QCOMPARE
(
uiInfo
->
command
(),
(
MAV_CMD
)
command
);
QCOMPARE
(
uiInfo
->
rawName
(),
_rawName
(
command
));
QCOMPARE
(
uiInfo
->
rawName
(),
_rawName
(
command
));
...
@@ -116,7 +116,7 @@ void MissionCommandTreeTest::_checkOverrideValues(const MissionCommandUIInfo* ui
...
@@ -116,7 +116,7 @@ void MissionCommandTreeTest::_checkOverrideValues(const MissionCommandUIInfo* ui
bool
showUI
;
bool
showUI
;
QString
overrideString
=
QString
(
"override fw %1"
).
arg
(
command
);
QString
overrideString
=
QString
(
"override fw %1"
).
arg
(
command
);
QVERIFY
(
uiInfo
!=
NULL
);
QVERIFY
(
uiInfo
!=
nullptr
);
_checkFullInfoMap
(
uiInfo
);
_checkFullInfoMap
(
uiInfo
);
QCOMPARE
(
uiInfo
->
command
(),
(
MAV_CMD
)
command
);
QCOMPARE
(
uiInfo
->
command
(),
(
MAV_CMD
)
command
);
QCOMPARE
(
uiInfo
->
rawName
(),
_rawName
(
command
));
QCOMPARE
(
uiInfo
->
rawName
(),
_rawName
(
command
));
...
@@ -143,11 +143,11 @@ void MissionCommandTreeTest::testJsonLoad(void)
...
@@ -143,11 +143,11 @@ void MissionCommandTreeTest::testJsonLoad(void)
// Test loading from the bad command list
// Test loading from the bad command list
MissionCommandList
*
commandList
=
_commandTree
->
_staticCommandTree
[
MAV_AUTOPILOT_GENERIC
][
MAV_TYPE_GENERIC
];
MissionCommandList
*
commandList
=
_commandTree
->
_staticCommandTree
[
MAV_AUTOPILOT_GENERIC
][
MAV_TYPE_GENERIC
];
QVERIFY
(
commandList
!=
NULL
);
QVERIFY
(
commandList
!=
nullptr
);
// Command 1 should have all values defaulted, no params
// Command 1 should have all values defaulted, no params
MissionCommandUIInfo
*
uiInfo
=
commandList
->
getUIInfo
((
MAV_CMD
)
1
);
MissionCommandUIInfo
*
uiInfo
=
commandList
->
getUIInfo
((
MAV_CMD
)
1
);
QVERIFY
(
uiInfo
!=
NULL
);
QVERIFY
(
uiInfo
!=
nullptr
);
_checkFullInfoMap
(
uiInfo
);
_checkFullInfoMap
(
uiInfo
);
QCOMPARE
(
uiInfo
->
command
(),
(
MAV_CMD
)
1
);
QCOMPARE
(
uiInfo
->
command
(),
(
MAV_CMD
)
1
);
QCOMPARE
(
uiInfo
->
rawName
(),
_rawName
(
1
));
QCOMPARE
(
uiInfo
->
rawName
(),
_rawName
(
1
));
...
@@ -158,13 +158,13 @@ void MissionCommandTreeTest::testJsonLoad(void)
...
@@ -158,13 +158,13 @@ void MissionCommandTreeTest::testJsonLoad(void)
QCOMPARE
(
uiInfo
->
isStandaloneCoordinate
(),
false
);
QCOMPARE
(
uiInfo
->
isStandaloneCoordinate
(),
false
);
QCOMPARE
(
uiInfo
->
specifiesCoordinate
(),
false
);
QCOMPARE
(
uiInfo
->
specifiesCoordinate
(),
false
);
for
(
int
i
=
1
;
i
<=
7
;
i
++
)
{
for
(
int
i
=
1
;
i
<=
7
;
i
++
)
{
QVERIFY
(
uiInfo
->
getParamInfo
(
i
,
showUI
)
==
NULL
);
QVERIFY
(
uiInfo
->
getParamInfo
(
i
,
showUI
)
==
nullptr
);
QCOMPARE
(
showUI
,
false
);
QCOMPARE
(
showUI
,
false
);
}
}
// Command 2 should all values defaulted for param 1
// Command 2 should all values defaulted for param 1
uiInfo
=
commandList
->
getUIInfo
((
MAV_CMD
)
2
);
uiInfo
=
commandList
->
getUIInfo
((
MAV_CMD
)
2
);
QVERIFY
(
uiInfo
!=
NULL
);
QVERIFY
(
uiInfo
!=
nullptr
);
const
MissionCmdParamInfo
*
paramInfo
=
uiInfo
->
getParamInfo
(
1
,
showUI
);
const
MissionCmdParamInfo
*
paramInfo
=
uiInfo
->
getParamInfo
(
1
,
showUI
);
QVERIFY
(
paramInfo
);
QVERIFY
(
paramInfo
);
QCOMPARE
(
showUI
,
true
);
QCOMPARE
(
showUI
,
true
);
...
@@ -176,7 +176,7 @@ void MissionCommandTreeTest::testJsonLoad(void)
...
@@ -176,7 +176,7 @@ void MissionCommandTreeTest::testJsonLoad(void)
QCOMPARE
(
paramInfo
->
param
(),
1
);
QCOMPARE
(
paramInfo
->
param
(),
1
);
QVERIFY
(
paramInfo
->
units
().
isEmpty
());
QVERIFY
(
paramInfo
->
units
().
isEmpty
());
for
(
int
i
=
2
;
i
<=
7
;
i
++
)
{
for
(
int
i
=
2
;
i
<=
7
;
i
++
)
{
QVERIFY
(
uiInfo
->
getParamInfo
(
i
,
showUI
)
==
NULL
);
QVERIFY
(
uiInfo
->
getParamInfo
(
i
,
showUI
)
==
nullptr
);
QCOMPARE
(
showUI
,
false
);
QCOMPARE
(
showUI
,
false
);
}
}
...
@@ -214,7 +214,7 @@ void MissionCommandTreeTest::testAllTrees(void)
...
@@ -214,7 +214,7 @@ void MissionCommandTreeTest::testAllTrees(void)
}
}
qDebug
()
<<
firmwareType
<<
vehicleType
;
qDebug
()
<<
firmwareType
<<
vehicleType
;
Vehicle
*
vehicle
=
new
Vehicle
(
firmwareType
,
vehicleType
,
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
());
Vehicle
*
vehicle
=
new
Vehicle
(
firmwareType
,
vehicleType
,
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
());
QVERIFY
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
()
->
getUIInfo
(
vehicle
,
MAV_CMD_NAV_WAYPOINT
)
!=
NULL
);
QVERIFY
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
()
->
getUIInfo
(
vehicle
,
MAV_CMD_NAV_WAYPOINT
)
!=
nullptr
);
delete
vehicle
;
delete
vehicle
;
}
}
}
}
...
...
src/MissionManager/MissionCommandUIInfo.h
View file @
343e5910
...
@@ -42,9 +42,9 @@ class MissionCmdParamInfo : public QObject {
...
@@ -42,9 +42,9 @@ class MissionCmdParamInfo : public QObject {
Q_OBJECT
Q_OBJECT
public:
public:
MissionCmdParamInfo
(
QObject
*
parent
=
NULL
);
MissionCmdParamInfo
(
QObject
*
parent
=
nullptr
);
MissionCmdParamInfo
(
const
MissionCmdParamInfo
&
other
,
QObject
*
parent
=
NULL
);
MissionCmdParamInfo
(
const
MissionCmdParamInfo
&
other
,
QObject
*
parent
=
nullptr
);
const
MissionCmdParamInfo
&
operator
=
(
const
MissionCmdParamInfo
&
other
);
const
MissionCmdParamInfo
&
operator
=
(
const
MissionCmdParamInfo
&
other
);
Q_PROPERTY
(
int
decimalPlaces
READ
decimalPlaces
CONSTANT
)
Q_PROPERTY
(
int
decimalPlaces
READ
decimalPlaces
CONSTANT
)
...
@@ -105,9 +105,9 @@ class MissionCommandUIInfo : public QObject {
...
@@ -105,9 +105,9 @@ class MissionCommandUIInfo : public QObject {
Q_OBJECT
Q_OBJECT
public:
public:
MissionCommandUIInfo
(
QObject
*
parent
=
NULL
);
MissionCommandUIInfo
(
QObject
*
parent
=
nullptr
);
MissionCommandUIInfo
(
const
MissionCommandUIInfo
&
other
,
QObject
*
parent
=
NULL
);
MissionCommandUIInfo
(
const
MissionCommandUIInfo
&
other
,
QObject
*
parent
=
nullptr
);
const
MissionCommandUIInfo
&
operator
=
(
const
MissionCommandUIInfo
&
other
);
const
MissionCommandUIInfo
&
operator
=
(
const
MissionCommandUIInfo
&
other
);
Q_PROPERTY
(
QString
category
READ
category
CONSTANT
)
Q_PROPERTY
(
QString
category
READ
category
CONSTANT
)
...
...
src/MissionManager/MissionController.cc
View file @
343e5910
...
@@ -1663,7 +1663,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
...
@@ -1663,7 +1663,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
void
MissionController
::
_deinitVisualItem
(
VisualMissionItem
*
visualItem
)
void
MissionController
::
_deinitVisualItem
(
VisualMissionItem
*
visualItem
)
{
{
// Disconnect all signals
// Disconnect all signals
disconnect
(
visualItem
,
0
,
0
,
0
);
disconnect
(
visualItem
,
nullptr
,
nullptr
,
nullptr
);
}
}
void
MissionController
::
_itemCommandChanged
(
void
)
void
MissionController
::
_itemCommandChanged
(
void
)
...
@@ -1677,8 +1677,8 @@ void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
...
@@ -1677,8 +1677,8 @@ void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
if
(
_managerVehicle
)
{
if
(
_managerVehicle
)
{
_missionManager
->
disconnect
(
this
);
_missionManager
->
disconnect
(
this
);
_managerVehicle
->
disconnect
(
this
);
_managerVehicle
->
disconnect
(
this
);
_managerVehicle
=
NULL
;
_managerVehicle
=
nullptr
;
_missionManager
=
NULL
;
_missionManager
=
nullptr
;
}
}
_managerVehicle
=
managerVehicle
;
_managerVehicle
=
managerVehicle
;
...
@@ -2056,7 +2056,7 @@ VisualMissionItem* MissionController::currentPlanViewItem(void) const
...
@@ -2056,7 +2056,7 @@ VisualMissionItem* MissionController::currentPlanViewItem(void) const
void
MissionController
::
setCurrentPlanViewIndex
(
int
sequenceNumber
,
bool
force
)
void
MissionController
::
setCurrentPlanViewIndex
(
int
sequenceNumber
,
bool
force
)
{
{
if
(
_visualItems
&&
(
force
||
sequenceNumber
!=
_currentPlanViewIndex
))
{
if
(
_visualItems
&&
(
force
||
sequenceNumber
!=
_currentPlanViewIndex
))
{
_currentPlanViewItem
=
NULL
;
_currentPlanViewItem
=
nullptr
;
_currentPlanViewIndex
=
-
1
;
_currentPlanViewIndex
=
-
1
;
for
(
int
i
=
0
;
i
<
_visualItems
->
count
();
i
++
)
{
for
(
int
i
=
0
;
i
<
_visualItems
->
count
();
i
++
)
{
VisualMissionItem
*
pVI
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
));
VisualMissionItem
*
pVI
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
));
...
...
src/MissionManager/MissionController.h
View file @
343e5910
...
@@ -40,7 +40,7 @@ class MissionController : public PlanElementController
...
@@ -40,7 +40,7 @@ class MissionController : public PlanElementController
Q_OBJECT
Q_OBJECT
public:
public:
MissionController
(
PlanMasterController
*
masterController
,
QObject
*
parent
=
NULL
);
MissionController
(
PlanMasterController
*
masterController
,
QObject
*
parent
=
nullptr
);
~
MissionController
();
~
MissionController
();
typedef
struct
_MissionFlightStatus_t
{
typedef
struct
_MissionFlightStatus_t
{
...
...
src/MissionManager/MissionControllerManagerTest.cc
View file @
343e5910
...
@@ -21,7 +21,7 @@ MissionControllerManagerTest::MissionControllerManagerTest(void)
...
@@ -21,7 +21,7 @@ MissionControllerManagerTest::MissionControllerManagerTest(void)
void
MissionControllerManagerTest
::
cleanup
(
void
)
void
MissionControllerManagerTest
::
cleanup
(
void
)
{
{
delete
_multiSpyMissionManager
;
delete
_multiSpyMissionManager
;
_multiSpyMissionManager
=
NULL
;
_multiSpyMissionManager
=
nullptr
;
UnitTest
::
cleanup
();
UnitTest
::
cleanup
();
}
}
...
...
src/MissionManager/MissionControllerTest.cc
View file @
343e5910
...
@@ -18,9 +18,9 @@
...
@@ -18,9 +18,9 @@
#include "AppSettings.h"
#include "AppSettings.h"
MissionControllerTest
::
MissionControllerTest
(
void
)
MissionControllerTest
::
MissionControllerTest
(
void
)
:
_multiSpyMissionController
(
NULL
)
:
_multiSpyMissionController
(
nullptr
)
,
_multiSpyMissionItem
(
NULL
)
,
_multiSpyMissionItem
(
nullptr
)
,
_missionController
(
NULL
)
,
_missionController
(
nullptr
)
{
{
}
}
...
@@ -28,13 +28,13 @@ MissionControllerTest::MissionControllerTest(void)
...
@@ -28,13 +28,13 @@ MissionControllerTest::MissionControllerTest(void)
void
MissionControllerTest
::
cleanup
(
void
)
void
MissionControllerTest
::
cleanup
(
void
)
{
{
delete
_masterController
;
delete
_masterController
;
_masterController
=
NULL
;
_masterController
=
nullptr
;
delete
_multiSpyMissionController
;
delete
_multiSpyMissionController
;
_multiSpyMissionController
=
NULL
;
_multiSpyMissionController
=
nullptr
;
delete
_multiSpyMissionItem
;
delete
_multiSpyMissionItem
;
_multiSpyMissionItem
=
NULL
;
_multiSpyMissionItem
=
nullptr
;
MissionControllerManagerTest
::
cleanup
();
MissionControllerManagerTest
::
cleanup
();
}
}
...
...
src/MissionManager/MissionItem.h
View file @
343e5910
...
@@ -38,7 +38,7 @@ class MissionItem : public QObject
...
@@ -38,7 +38,7 @@ class MissionItem : public QObject
Q_OBJECT
Q_OBJECT
public:
public:
MissionItem
(
QObject
*
parent
=
NULL
);
MissionItem
(
QObject
*
parent
=
nullptr
);
MissionItem
(
int
sequenceNumber
,
MissionItem
(
int
sequenceNumber
,
MAV_CMD
command
,
MAV_CMD
command
,
...
@@ -52,9 +52,9 @@ public:
...
@@ -52,9 +52,9 @@ public:
double
param7
,
double
param7
,
bool
autoContinue
,
bool
autoContinue
,
bool
isCurrentItem
,
bool
isCurrentItem
,
QObject
*
parent
=
NULL
);
QObject
*
parent
=
nullptr
);
MissionItem
(
const
MissionItem
&
other
,
QObject
*
parent
=
NULL
);
MissionItem
(
const
MissionItem
&
other
,
QObject
*
parent
=
nullptr
);
~
MissionItem
();
~
MissionItem
();
...
...
src/MissionManager/MissionItemTest.cc
View file @
343e5910
...
@@ -28,7 +28,7 @@ const size_t MissionItemTest::_cTestCases = sizeof(_rgTestCases)/sizeof(_rgTestC
...
@@ -28,7 +28,7 @@ const size_t MissionItemTest::_cTestCases = sizeof(_rgTestCases)/sizeof(_rgTestC
#endif
#endif
MissionItemTest
::
MissionItemTest
(
void
)
MissionItemTest
::
MissionItemTest
(
void
)
:
_offlineVehicle
(
NULL
)
:
_offlineVehicle
(
nullptr
)
{
{
}
}
...
@@ -282,7 +282,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void)
...
@@ -282,7 +282,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void)
{
{
// We specifically test SimpleMissionItem loading as well since it has additional
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
// signalling which can affect values.
SimpleMissionItem
simpleMissionItem
(
_offlineVehicle
,
false
/* flyView */
,
NULL
);
SimpleMissionItem
simpleMissionItem
(
_offlineVehicle
,
false
/* flyView */
,
nullptr
);
QString
testString
(
"10
\t
0
\t
3
\t
80
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
);
QString
testString
(
"10
\t
0
\t
3
\t
80
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
);
QTextStream
testStream
(
&
testString
,
QIODevice
::
ReadOnly
);
QTextStream
testStream
(
&
testString
,
QIODevice
::
ReadOnly
);
...
@@ -452,7 +452,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void)
...
@@ -452,7 +452,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void)
// We specifically test SimpleMissionItem loading as well since it has additional
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
// signalling which can affect values.
SimpleMissionItem
simpleMissionItem
(
_offlineVehicle
,
false
/* flyView */
,
NULL
);
SimpleMissionItem
simpleMissionItem
(
_offlineVehicle
,
false
/* flyView */
,
nullptr
);
QString
errorString
;
QString
errorString
;
QJsonArray
coordinateArray
;
QJsonArray
coordinateArray
;
QJsonObject
jsonObject
;
QJsonObject
jsonObject
;
...
...
src/MissionManager/MissionManagerTest.cc
View file @
343e5910
...
@@ -35,7 +35,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
...
@@ -35,7 +35,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
QList
<
MissionItem
*>
missionItems
;
QList
<
MissionItem
*>
missionItems
;
// Editor has a home position item on the front, so we do the same
// Editor has a home position item on the front, so we do the same
MissionItem
*
homeItem
=
new
MissionItem
(
NULL
/* Vehicle */
,
this
);
MissionItem
*
homeItem
=
new
MissionItem
(
nullptr
/* Vehicle */
,
this
);
homeItem
->
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
homeItem
->
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
homeItem
->
setParam5
(
47.3769
);
homeItem
->
setParam5
(
47.3769
);
homeItem
->
setParam6
(
8.549444
);
homeItem
->
setParam6
(
8.549444
);
...
...
src/MissionManager/MissionSettingsItem.cc
View file @
343e5910
...
@@ -40,7 +40,7 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject
...
@@ -40,7 +40,7 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject
_editorQml
=
"qrc:/qml/MissionSettingsEditor.qml"
;
_editorQml
=
"qrc:/qml/MissionSettingsEditor.qml"
;
if
(
_metaDataMap
.
isEmpty
())
{
if
(
_metaDataMap
.
isEmpty
())
{
_metaDataMap
=
FactMetaData
::
createMapFromJsonFile
(
QStringLiteral
(
":/json/MissionSettings.FactMetaData.json"
),
NULL
/* metaDataParent */
);
_metaDataMap
=
FactMetaData
::
createMapFromJsonFile
(
QStringLiteral
(
":/json/MissionSettings.FactMetaData.json"
),
nullptr
/* metaDataParent */
);
}
}
_plannedHomePositionAltitudeFact
.
setMetaData
(
_metaDataMap
[
_plannedHomePositionAltitudeName
]);
_plannedHomePositionAltitudeFact
.
setMetaData
(
_metaDataMap
[
_plannedHomePositionAltitudeName
]);
...
@@ -163,7 +163,7 @@ void MissionSettingsItem::appendMissionItems(QList<MissionItem*>& items, QObject
...
@@ -163,7 +163,7 @@ void MissionSettingsItem::appendMissionItems(QList<MissionItem*>& items, QObject
bool
MissionSettingsItem
::
addMissionEndAction
(
QList
<
MissionItem
*>&
items
,
int
seqNum
,
QObject
*
missionItemParent
)
bool
MissionSettingsItem
::
addMissionEndAction
(
QList
<
MissionItem
*>&
items
,
int
seqNum
,
QObject
*
missionItemParent
)
{
{
MissionItem
*
item
=
NULL
;
MissionItem
*
item
=
nullptr
;
// IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings
// IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings
...
...
src/MissionManager/MissionSettingsTest.cc
View file @
343e5910
...
@@ -13,7 +13,7 @@
...
@@ -13,7 +13,7 @@
#include "SettingsManager.h"
#include "SettingsManager.h"
MissionSettingsTest
::
MissionSettingsTest
(
void
)
MissionSettingsTest
::
MissionSettingsTest
(
void
)
:
_settingsItem
(
NULL
)
:
_settingsItem
(
nullptr
)
{
{
}
}
...
...
src/MissionManager/PlanElementController.h
View file @
343e5910
...
@@ -24,7 +24,7 @@ class PlanElementController : public QObject
...
@@ -24,7 +24,7 @@ class PlanElementController : public QObject
Q_OBJECT
Q_OBJECT
public:
public:
PlanElementController
(
PlanMasterController
*
masterController
,
QObject
*
parent
=
NULL
);
PlanElementController
(
PlanMasterController
*
masterController
,
QObject
*
parent
=
nullptr
);
~
PlanElementController
();
~
PlanElementController
();
Q_PROPERTY
(
bool
supported
READ
supported
NOTIFY
supportedChanged
)
///< true: Element is supported by Vehicle
Q_PROPERTY
(
bool
supported
READ
supported
NOTIFY
supportedChanged
)
///< true: Element is supported by Vehicle
...
...
src/MissionManager/PlanManager.cc
View file @
343e5910
...
@@ -24,8 +24,8 @@ QGC_LOGGING_CATEGORY(PlanManagerLog, "PlanManagerLog")
...
@@ -24,8 +24,8 @@ QGC_LOGGING_CATEGORY(PlanManagerLog, "PlanManagerLog")
PlanManager
::
PlanManager
(
Vehicle
*
vehicle
,
MAV_MISSION_TYPE
planType
)
PlanManager
::
PlanManager
(
Vehicle
*
vehicle
,
MAV_MISSION_TYPE
planType
)
:
_vehicle
(
vehicle
)
:
_vehicle
(
vehicle
)
,
_planType
(
planType
)
,
_planType
(
planType
)
,
_dedicatedLink
(
NULL
)
,
_dedicatedLink
(
nullptr
)
,
_ackTimeoutTimer
(
NULL
)
,
_ackTimeoutTimer
(
nullptr
)
,
_expectedAck
(
AckNone
)
,
_expectedAck
(
AckNone
)
,
_transactionInProgress
(
TransactionNone
)
,
_transactionInProgress
(
TransactionNone
)
,
_resumeMission
(
false
)
,
_resumeMission
(
false
)
...
...
src/MissionManager/PlanMasterController.h
View file @
343e5910
...
@@ -26,7 +26,7 @@ class PlanMasterController : public QObject
...
@@ -26,7 +26,7 @@ class PlanMasterController : public QObject
Q_OBJECT
Q_OBJECT
public:
public:
PlanMasterController
(
QObject
*
parent
=
NULL
);
PlanMasterController
(
QObject
*
parent
=
nullptr
);
~
PlanMasterController
();
~
PlanMasterController
();
Q_PROPERTY
(
MissionController
*
missionController
READ
missionController
CONSTANT
)
Q_PROPERTY
(
MissionController
*
missionController
READ
missionController
CONSTANT
)
...
...
src/MissionManager/PlanMasterControllerTest.cc
View file @
343e5910
...
@@ -17,7 +17,7 @@
...
@@ -17,7 +17,7 @@
#include "AppSettings.h"
#include "AppSettings.h"
PlanMasterControllerTest
::
PlanMasterControllerTest
(
void
)
PlanMasterControllerTest
::
PlanMasterControllerTest
(
void
)
:
_masterController
(
NULL
)
:
_masterController
(
nullptr
)
{
{
}
}
...
@@ -33,7 +33,7 @@ void PlanMasterControllerTest::init(void)
...
@@ -33,7 +33,7 @@ void PlanMasterControllerTest::init(void)
void
PlanMasterControllerTest
::
cleanup
(
void
)
void
PlanMasterControllerTest
::
cleanup
(
void
)
{
{
delete
_masterController
;
delete
_masterController
;
_masterController
=
NULL
;
_masterController
=
nullptr
;
UnitTest
::
cleanup
();
UnitTest
::
cleanup
();
}
}
...
...
src/MissionManager/QGCFenceCircle.h
View file @
343e5910
...
@@ -17,9 +17,9 @@ class QGCFenceCircle : public QGCMapCircle
...
@@ -17,9 +17,9 @@ class QGCFenceCircle : public QGCMapCircle
Q_OBJECT
Q_OBJECT
public:
public:
QGCFenceCircle
(
QObject
*
parent
=
NULL
);
QGCFenceCircle
(
QObject
*
parent
=
nullptr
);
QGCFenceCircle
(
const
QGeoCoordinate
&
center
,
double
radius
,
bool
inclusion
,
QObject
*
parent
=
NULL
);
QGCFenceCircle
(
const
QGeoCoordinate
&
center
,
double
radius
,
bool
inclusion
,
QObject
*
parent
=
nullptr
);
QGCFenceCircle
(
const
QGCFenceCircle
&
other
,
QObject
*
parent
=
NULL
);
QGCFenceCircle
(
const
QGCFenceCircle
&
other
,
QObject
*
parent
=
nullptr
);
const
QGCFenceCircle
&
operator
=
(
const
QGCFenceCircle
&
other
);
const
QGCFenceCircle
&
operator
=
(
const
QGCFenceCircle
&
other
);
...
...
src/MissionManager/QGCFencePolygon.h
View file @
343e5910
...
@@ -17,8 +17,8 @@ class QGCFencePolygon : public QGCMapPolygon
...
@@ -17,8 +17,8 @@ class QGCFencePolygon : public QGCMapPolygon
Q_OBJECT
Q_OBJECT
public:
public:
QGCFencePolygon
(
bool
inclusion
,
QObject
*
parent
=
NULL
);
QGCFencePolygon
(
bool
inclusion
,
QObject
*
parent
=
nullptr
);
QGCFencePolygon
(
const
QGCFencePolygon
&
other
,
QObject
*
parent
=
NULL
);
QGCFencePolygon
(
const
QGCFencePolygon
&
other
,
QObject
*
parent
=
nullptr
);
const
QGCFencePolygon
&
operator
=
(
const
QGCFencePolygon
&
other
);
const
QGCFencePolygon
&
operator
=
(
const
QGCFencePolygon
&
other
);
...
...
src/MissionManager/QGCMapPolyline.h
View file @
343e5910
...
@@ -20,8 +20,8 @@ class QGCMapPolyline : public QObject
...
@@ -20,8 +20,8 @@ class QGCMapPolyline : public QObject
Q_OBJECT
Q_OBJECT
public:
public:
QGCMapPolyline
(
QObject
*
parent
=
NULL
);
QGCMapPolyline
(
QObject
*
parent
=
nullptr
);
QGCMapPolyline
(
const
QGCMapPolyline
&
other
,
QObject
*
parent
=
NULL
);
QGCMapPolyline
(
const
QGCMapPolyline
&
other
,
QObject
*
parent
=
nullptr
);
const
QGCMapPolyline
&
operator
=
(
const
QGCMapPolyline
&
other
);
const
QGCMapPolyline
&
operator
=
(
const
QGCMapPolyline
&
other
);
...
...
src/MissionManager/RallyPoint.cc
View file @
343e5910
...
@@ -64,7 +64,7 @@ RallyPoint::~RallyPoint()
...
@@ -64,7 +64,7 @@ RallyPoint::~RallyPoint()
void
RallyPoint
::
_factSetup
(
void
)
void
RallyPoint
::
_factSetup
(
void
)
{
{
if
(
_metaDataMap
.
isEmpty
())
{
if
(
_metaDataMap
.
isEmpty
())
{
_metaDataMap
=
FactMetaData
::
createMapFromJsonFile
(
QStringLiteral
(
":/json/RallyPoint.FactMetaData.json"
),
NULL
/* metaDataParent */
);
_metaDataMap
=
FactMetaData
::
createMapFromJsonFile
(
QStringLiteral
(
":/json/RallyPoint.FactMetaData.json"
),
nullptr
/* metaDataParent */
);
}
}
_longitudeFact
.
setMetaData
(
_metaDataMap
[
_longitudeFactName
]);
_longitudeFact
.
setMetaData
(
_metaDataMap
[
_longitudeFactName
]);
...
...
src/MissionManager/RallyPoint.h
View file @
343e5910
...
@@ -22,8 +22,8 @@ class RallyPoint : public QObject
...
@@ -22,8 +22,8 @@ class RallyPoint : public QObject
Q_OBJECT
Q_OBJECT
public:
public:
RallyPoint
(
const
QGeoCoordinate
&
coordinate
,
QObject
*
parent
=
NULL
);
RallyPoint
(
const
QGeoCoordinate
&
coordinate
,
QObject
*
parent
=
nullptr
);
RallyPoint
(
const
RallyPoint
&
other
,
QObject
*
parent
=
NULL
);
RallyPoint
(
const
RallyPoint
&
other
,
QObject
*
parent
=
nullptr
);
~
RallyPoint
();
~
RallyPoint
();
...
...
src/MissionManager/RallyPointController.cc
View file @
343e5910
...
@@ -37,7 +37,7 @@ RallyPointController::RallyPointController(PlanMasterController* masterControlle
...
@@ -37,7 +37,7 @@ RallyPointController::RallyPointController(PlanMasterController* masterControlle
:
PlanElementController
(
masterController
,
parent
)
:
PlanElementController
(
masterController
,
parent
)
,
_rallyPointManager
(
_managerVehicle
->
rallyPointManager
())
,
_rallyPointManager
(
_managerVehicle
->
rallyPointManager
())
,
_dirty
(
false
)
,
_dirty
(
false
)
,
_currentRallyPoint
(
NULL
)
,
_currentRallyPoint
(
nullptr
)
,
_itemsRequested
(
false
)
,
_itemsRequested
(
false
)
{
{
connect
(
&
_points
,
&
QmlObjectListModel
::
countChanged
,
this
,
&
RallyPointController
::
_updateContainsItems
);
connect
(
&
_points
,
&
QmlObjectListModel
::
countChanged
,
this
,
&
RallyPointController
::
_updateContainsItems
);
...
@@ -55,8 +55,8 @@ void RallyPointController::managerVehicleChanged(Vehicle* managerVehicle)
...
@@ -55,8 +55,8 @@ void RallyPointController::managerVehicleChanged(Vehicle* managerVehicle)
if
(
_managerVehicle
)
{
if
(
_managerVehicle
)
{
_rallyPointManager
->
disconnect
(
this
);
_rallyPointManager
->
disconnect
(
this
);
_managerVehicle
->
disconnect
(
this
);
_managerVehicle
->
disconnect
(
this
);
_managerVehicle
=
NULL
;
_managerVehicle
=
nullptr
;
_rallyPointManager
=
NULL
;
_rallyPointManager
=
nullptr
;
}
}
_managerVehicle
=
managerVehicle
;
_managerVehicle
=
managerVehicle
;
...
@@ -138,7 +138,7 @@ void RallyPointController::removeAll(void)
...
@@ -138,7 +138,7 @@ void RallyPointController::removeAll(void)
{
{
_points
.
clearAndDeleteContents
();
_points
.
clearAndDeleteContents
();
setDirty
(
true
);
setDirty
(
true
);
setCurrentRallyPoint
(
NULL
);
setCurrentRallyPoint
(
nullptr
);
}
}
void
RallyPointController
::
removeAllFromVehicle
(
void
)
void
RallyPointController
::
removeAllFromVehicle
(
void
)
...
@@ -268,7 +268,7 @@ void RallyPointController::removePoint(QObject* rallyPoint)
...
@@ -268,7 +268,7 @@ void RallyPointController::removePoint(QObject* rallyPoint)
newIndex
=
qMax
(
newIndex
,
0
);
newIndex
=
qMax
(
newIndex
,
0
);
setCurrentRallyPoint
(
_points
[
newIndex
]);
setCurrentRallyPoint
(
_points
[
newIndex
]);
}
else
{
}
else
{
setCurrentRallyPoint
(
NULL
);
setCurrentRallyPoint
(
nullptr
);
}
}
}
}
...
@@ -282,7 +282,7 @@ void RallyPointController::setCurrentRallyPoint(QObject* rallyPoint)
...
@@ -282,7 +282,7 @@ void RallyPointController::setCurrentRallyPoint(QObject* rallyPoint)
void
RallyPointController
::
_setFirstPointCurrent
(
void
)
void
RallyPointController
::
_setFirstPointCurrent
(
void
)
{
{
setCurrentRallyPoint
(
_points
.
count
()
?
_points
[
0
]
:
NULL
);
setCurrentRallyPoint
(
_points
.
count
()
?
_points
[
0
]
:
nullptr
);
}
}
bool
RallyPointController
::
containsItems
(
void
)
const
bool
RallyPointController
::
containsItems
(
void
)
const
...
...
src/MissionManager/RallyPointController.h
View file @
343e5910
...
@@ -26,7 +26,7 @@ class RallyPointController : public PlanElementController
...
@@ -26,7 +26,7 @@ class RallyPointController : public PlanElementController
Q_OBJECT
Q_OBJECT
public:
public:
RallyPointController
(
PlanMasterController
*
masterController
,
QObject
*
parent
=
NULL
);
RallyPointController
(
PlanMasterController
*
masterController
,
QObject
*
parent
=
nullptr
);
~
RallyPointController
();
~
RallyPointController
();
Q_PROPERTY
(
QmlObjectListModel
*
points
READ
points
CONSTANT
)
Q_PROPERTY
(
QmlObjectListModel
*
points
READ
points
CONSTANT
)
...
...
src/MissionManager/Section.h
View file @
343e5910
...
@@ -21,7 +21,7 @@ class Section : public QObject
...
@@ -21,7 +21,7 @@ class Section : public QObject
Q_OBJECT
Q_OBJECT
public:
public:
Section
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
)
Section
(
Vehicle
*
vehicle
,
QObject
*
parent
=
nullptr
)
:
QObject
(
parent
)
:
QObject
(
parent
)
,
_vehicle
(
vehicle
)
,
_vehicle
(
vehicle
)
{
{
...
...
src/MissionManager/SectionTest.cc
View file @
343e5910
...
@@ -11,7 +11,7 @@
...
@@ -11,7 +11,7 @@
#include "SurveyComplexItem.h"
#include "SurveyComplexItem.h"
SectionTest
::
SectionTest
(
void
)
SectionTest
::
SectionTest
(
void
)
:
_simpleItem
(
NULL
)
:
_simpleItem
(
nullptr
)
{
{
}
}
...
@@ -48,7 +48,7 @@ void SectionTest::cleanup(void)
...
@@ -48,7 +48,7 @@ void SectionTest::cleanup(void)
void
SectionTest
::
_createSpy
(
Section
*
section
,
MultiSignalSpy
**
sectionSpy
)
void
SectionTest
::
_createSpy
(
Section
*
section
,
MultiSignalSpy
**
sectionSpy
)
{
{
*
sectionSpy
=
NULL
;
*
sectionSpy
=
nullptr
;
MultiSignalSpy
*
spy
=
new
MultiSignalSpy
();
MultiSignalSpy
*
spy
=
new
MultiSignalSpy
();
QCOMPARE
(
spy
->
init
(
section
,
rgSectionSignals
,
cSectionSignals
),
true
);
QCOMPARE
(
spy
->
init
(
section
,
rgSectionSignals
,
cSectionSignals
),
true
);
*
sectionSpy
=
spy
;
*
sectionSpy
=
spy
;
...
...
src/MissionManager/SpeedSection.cc
View file @
343e5910
...
@@ -24,7 +24,7 @@ SpeedSection::SpeedSection(Vehicle* vehicle, QObject* parent)
...
@@ -24,7 +24,7 @@ SpeedSection::SpeedSection(Vehicle* vehicle, QObject* parent)
,
_flightSpeedFact
(
0
,
_flightSpeedName
,
FactMetaData
::
valueTypeDouble
)
,
_flightSpeedFact
(
0
,
_flightSpeedName
,
FactMetaData
::
valueTypeDouble
)
{
{
if
(
_metaDataMap
.
isEmpty
())
{
if
(
_metaDataMap
.
isEmpty
())
{
_metaDataMap
=
FactMetaData
::
createMapFromJsonFile
(
QStringLiteral
(
":/json/SpeedSection.FactMetaData.json"
),
NULL
/* metaDataParent */
);
_metaDataMap
=
FactMetaData
::
createMapFromJsonFile
(
QStringLiteral
(
":/json/SpeedSection.FactMetaData.json"
),
nullptr
/* metaDataParent */
);
}
}
double
flightSpeed
=
0
;
double
flightSpeed
=
0
;
...
...
src/MissionManager/SpeedSection.h
View file @
343e5910
...
@@ -18,7 +18,7 @@ class SpeedSection : public Section
...
@@ -18,7 +18,7 @@ class SpeedSection : public Section
Q_OBJECT
Q_OBJECT
public:
public:
SpeedSection
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
SpeedSection
(
Vehicle
*
vehicle
,
QObject
*
parent
=
nullptr
);
Q_PROPERTY
(
bool
specifyFlightSpeed
READ
specifyFlightSpeed
WRITE
setSpecifyFlightSpeed
NOTIFY
specifyFlightSpeedChanged
)
Q_PROPERTY
(
bool
specifyFlightSpeed
READ
specifyFlightSpeed
WRITE
setSpecifyFlightSpeed
NOTIFY
specifyFlightSpeedChanged
)
Q_PROPERTY
(
Fact
*
flightSpeed
READ
flightSpeed
CONSTANT
)
Q_PROPERTY
(
Fact
*
flightSpeed
READ
flightSpeed
CONSTANT
)
...
...
src/MissionManager/SpeedSectionTest.cc
View file @
343e5910
...
@@ -10,9 +10,9 @@
...
@@ -10,9 +10,9 @@
#include "SpeedSectionTest.h"
#include "SpeedSectionTest.h"
SpeedSectionTest
::
SpeedSectionTest
(
void
)
SpeedSectionTest
::
SpeedSectionTest
(
void
)
:
_spySpeed
(
NULL
)
:
_spySpeed
(
nullptr
)
,
_spySection
(
NULL
)
,
_spySection
(
nullptr
)
,
_speedSection
(
NULL
)
,
_speedSection
(
nullptr
)
{
{
}
}
...
@@ -39,7 +39,7 @@ void SpeedSectionTest::cleanup(void)
...
@@ -39,7 +39,7 @@ void SpeedSectionTest::cleanup(void)
void
SpeedSectionTest
::
_createSpy
(
SpeedSection
*
speedSection
,
MultiSignalSpy
**
speedSpy
)
void
SpeedSectionTest
::
_createSpy
(
SpeedSection
*
speedSection
,
MultiSignalSpy
**
speedSpy
)
{
{
*
speedSpy
=
NULL
;
*
speedSpy
=
nullptr
;
MultiSignalSpy
*
spy
=
new
MultiSignalSpy
();
MultiSignalSpy
*
spy
=
new
MultiSignalSpy
();
QCOMPARE
(
spy
->
init
(
speedSection
,
rgSpeedSignals
,
cSpeedSignals
),
true
);
QCOMPARE
(
spy
->
init
(
speedSection
,
rgSpeedSignals
,
cSpeedSignals
),
true
);
*
speedSpy
=
spy
;
*
speedSpy
=
spy
;
...
@@ -193,7 +193,7 @@ void SpeedSectionTest::_testScanForSection(void)
...
@@ -193,7 +193,7 @@ void SpeedSectionTest::_testScanForSection(void)
double
flightSpeed
=
10.123456
;
double
flightSpeed
=
10.123456
;
MissionItem
validSpeedItem
(
0
,
MAV_CMD_DO_CHANGE_SPEED
,
MAV_FRAME_MISSION
,
_offlineVehicle
->
multiRotor
()
?
1
:
0
,
flightSpeed
,
-
1
,
0
,
0
,
0
,
0
,
true
,
false
);
MissionItem
validSpeedItem
(
0
,
MAV_CMD_DO_CHANGE_SPEED
,
MAV_FRAME_MISSION
,
_offlineVehicle
->
multiRotor
()
?
1
:
0
,
flightSpeed
,
-
1
,
0
,
0
,
0
,
0
,
true
,
false
);
SimpleMissionItem
simpleItem
(
_offlineVehicle
,
false
/* flyView */
,
validSpeedItem
,
NULL
);
SimpleMissionItem
simpleItem
(
_offlineVehicle
,
false
/* flyView */
,
validSpeedItem
,
nullptr
);
MissionItem
&
simpleMissionItem
=
simpleItem
.
missionItem
();
MissionItem
&
simpleMissionItem
=
simpleItem
.
missionItem
();
visualItems
.
append
(
&
simpleItem
);
visualItems
.
append
(
&
simpleItem
);
scanIndex
=
0
;
scanIndex
=
0
;
...
@@ -264,7 +264,7 @@ void SpeedSectionTest::_testScanForSection(void)
...
@@ -264,7 +264,7 @@ void SpeedSectionTest::_testScanForSection(void)
// Valid item in wrong position
// Valid item in wrong position
MissionItem
waypointMissionItem
(
0
,
MAV_CMD_NAV_WAYPOINT
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
true
,
false
);
MissionItem
waypointMissionItem
(
0
,
MAV_CMD_NAV_WAYPOINT
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
true
,
false
);
SimpleMissionItem
simpleWaypointItem
(
_offlineVehicle
,
false
/* flyView */
,
waypointMissionItem
,
NULL
);
SimpleMissionItem
simpleWaypointItem
(
_offlineVehicle
,
false
/* flyView */
,
waypointMissionItem
,
nullptr
);
simpleMissionItem
=
validSpeedItem
;
simpleMissionItem
=
validSpeedItem
;
visualItems
.
append
(
&
simpleWaypointItem
);
visualItems
.
append
(
&
simpleWaypointItem
);
visualItems
.
append
(
&
simpleMissionItem
);
visualItems
.
append
(
&
simpleMissionItem
);
...
...
src/MissionManager/SurveyComplexItemTest.cc
View file @
343e5910
...
@@ -11,7 +11,7 @@
...
@@ -11,7 +11,7 @@
#include "QGCApplication.h"
#include "QGCApplication.h"
SurveyComplexItemTest
::
SurveyComplexItemTest
(
void
)
SurveyComplexItemTest
::
SurveyComplexItemTest
(
void
)
:
_offlineVehicle
(
NULL
)
:
_offlineVehicle
(
nullptr
)
{
{
_polyPoints
<<
QGeoCoordinate
(
47.633550640000003
,
-
122.08982199
)
<<
QGeoCoordinate
(
47.634129020000003
,
-
122.08887249
)
<<
_polyPoints
<<
QGeoCoordinate
(
47.633550640000003
,
-
122.08982199
)
<<
QGeoCoordinate
(
47.634129020000003
,
-
122.08887249
)
<<
QGeoCoordinate
(
47.633619320000001
,
-
122.08811074
)
<<
QGeoCoordinate
(
47.633189139999999
,
-
122.08900124
);
QGeoCoordinate
(
47.633619320000001
,
-
122.08811074
)
<<
QGeoCoordinate
(
47.633189139999999
,
-
122.08900124
);
...
...
src/MissionManager/TransectStyleComplexItemTest.cc
View file @
343e5910
...
@@ -11,7 +11,7 @@
...
@@ -11,7 +11,7 @@
#include "QGCApplication.h"
#include "QGCApplication.h"
TransectStyleComplexItemTest
::
TransectStyleComplexItemTest
(
void
)
TransectStyleComplexItemTest
::
TransectStyleComplexItemTest
(
void
)
:
_offlineVehicle
(
NULL
)
:
_offlineVehicle
(
nullptr
)
{
{
_polygonVertices
<<
QGeoCoordinate
(
47.633550640000003
,
-
122.08982199
)
_polygonVertices
<<
QGeoCoordinate
(
47.633550640000003
,
-
122.08982199
)
<<
QGeoCoordinate
(
47.634129020000003
,
-
122.08887249
)
<<
QGeoCoordinate
(
47.634129020000003
,
-
122.08887249
)
...
...
src/MissionManager/TransectStyleComplexItemTest.h
View file @
343e5910
...
@@ -83,7 +83,7 @@ class TransectStyleItem : public TransectStyleComplexItem
...
@@ -83,7 +83,7 @@ class TransectStyleItem : public TransectStyleComplexItem
Q_OBJECT
Q_OBJECT
public:
public:
TransectStyleItem
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
TransectStyleItem
(
Vehicle
*
vehicle
,
QObject
*
parent
=
nullptr
);
// Overrides from ComplexMissionItem
// Overrides from ComplexMissionItem
QString
mapVisualQML
(
void
)
const
final
{
return
QString
();
}
QString
mapVisualQML
(
void
)
const
final
{
return
QString
();
}
...
...
src/MissionManager/VisualMissionItemTest.cc
View file @
343e5910
...
@@ -12,7 +12,7 @@
...
@@ -12,7 +12,7 @@
#include "QGCApplication.h"
#include "QGCApplication.h"
VisualMissionItemTest
::
VisualMissionItemTest
(
void
)
VisualMissionItemTest
::
VisualMissionItemTest
(
void
)
:
_offlineVehicle
(
NULL
)
:
_offlineVehicle
(
nullptr
)
{
{
}
}
...
@@ -60,7 +60,7 @@ void VisualMissionItemTest::cleanup(void)
...
@@ -60,7 +60,7 @@ void VisualMissionItemTest::cleanup(void)
void
VisualMissionItemTest
::
_createSpy
(
SimpleMissionItem
*
simpleItem
,
MultiSignalSpy
**
visualSpy
)
void
VisualMissionItemTest
::
_createSpy
(
SimpleMissionItem
*
simpleItem
,
MultiSignalSpy
**
visualSpy
)
{
{
*
visualSpy
=
NULL
;
*
visualSpy
=
nullptr
;
MultiSignalSpy
*
spy
=
new
MultiSignalSpy
();
MultiSignalSpy
*
spy
=
new
MultiSignalSpy
();
QCOMPARE
(
spy
->
init
(
simpleItem
,
rgVisualItemSignals
,
cVisualItemSignals
),
true
);
QCOMPARE
(
spy
->
init
(
simpleItem
,
rgVisualItemSignals
,
cVisualItemSignals
),
true
);
*
visualSpy
=
spy
;
*
visualSpy
=
spy
;
...
...
src/PositionManager/PositionManager.cpp
View file @
343e5910
...
@@ -15,10 +15,10 @@ QGCPositionManager::QGCPositionManager(QGCApplication* app, QGCToolbox* toolbox)
...
@@ -15,10 +15,10 @@ QGCPositionManager::QGCPositionManager(QGCApplication* app, QGCToolbox* toolbox)
:
QGCTool
(
app
,
toolbox
)
:
QGCTool
(
app
,
toolbox
)
,
_updateInterval
(
0
)
,
_updateInterval
(
0
)
,
_gcsHeading
(
NAN
)
,
_gcsHeading
(
NAN
)
,
_currentSource
(
NULL
)
,
_currentSource
(
nullptr
)
,
_defaultSource
(
NULL
)
,
_defaultSource
(
nullptr
)
,
_nmeaSource
(
NULL
)
,
_nmeaSource
(
nullptr
)
,
_simulatedSource
(
NULL
)
,
_simulatedSource
(
nullptr
)
{
{
}
}
...
...
src/PositionManager/SimulatedPosition.cc
View file @
343e5910
...
@@ -16,7 +16,7 @@
...
@@ -16,7 +16,7 @@
SimulatedPosition
::
simulated_motion_s
SimulatedPosition
::
_simulated_motion
[
5
]
=
{{
0
,
250
},{
0
,
0
},{
0
,
-
250
},{
-
250
,
0
},{
0
,
0
}};
SimulatedPosition
::
simulated_motion_s
SimulatedPosition
::
_simulated_motion
[
5
]
=
{{
0
,
250
},{
0
,
0
},{
0
,
-
250
},{
-
250
,
0
},{
0
,
0
}};
SimulatedPosition
::
SimulatedPosition
()
SimulatedPosition
::
SimulatedPosition
()
:
QGeoPositionInfoSource
(
NULL
),
:
QGeoPositionInfoSource
(
nullptr
),
lat_int
(
47.3977420
*
1e7
),
lat_int
(
47.3977420
*
1e7
),
lon_int
(
8.5455941
*
1e7
),
lon_int
(
8.5455941
*
1e7
),
_step_cnt
(
0
),
_step_cnt
(
0
),
...
...
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