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
00e404d0
Unverified
Commit
00e404d0
authored
5 years ago
by
Don Gagne
Committed by
GitHub
5 years ago
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #7827 from DonLakeFlyer/FlightTrajectory
New flight trajectory display algorithm
parents
8d325b21
978eb86c
Changes
9
Hide whitespace changes
Inline
Side-by-side
Showing
9 changed files
with
177 additions
and
84 deletions
+177
-84
ChangeLog.md
ChangeLog.md
+1
-0
qgroundcontrol.pro
qgroundcontrol.pro
+13
-12
FlightDisplayViewMap.qml
src/FlightDisplay/FlightDisplayViewMap.qml
+19
-11
QGCApplication.cc
src/QGCApplication.cc
+2
-0
TrajectoryPoints.cc
src/Vehicle/TrajectoryPoints.cc
+60
-0
TrajectoryPoints.h
src/Vehicle/TrajectoryPoints.h
+49
-0
Vehicle.cc
src/Vehicle/Vehicle.cc
+22
-36
Vehicle.h
src/Vehicle/Vehicle.h
+11
-17
UASMessageHandler.h
src/uas/UASMessageHandler.h
+0
-8
No files found.
ChangeLog.md
View file @
00e404d0
...
@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
...
@@ -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
*
More performant flight path display algorithm. Mobile builds no longer show limited path length.
*
ArduCopter/Rover: Add support for Follow Me
*
ArduCopter/Rover: Add support for Follow Me
*
ArduPilot: Add Motor Test vehicle setup page
*
ArduPilot: Add Motor Test vehicle setup page
*
Compass Instrument: Add indicators for Home, COG and Next Waypoint headings.
*
Compass Instrument: Add indicators for Home, COG and Next Waypoint headings.
...
...
This diff is collapsed.
Click to expand it.
qgroundcontrol.pro
View file @
00e404d0
...
@@ -416,7 +416,7 @@ INCLUDEPATH += \
...
@@ -416,7 +416,7 @@ INCLUDEPATH += \
src
/
QtLocationPlugin
/
QMLControl
\
src
/
QtLocationPlugin
/
QMLControl
\
src
/
Settings
\
src
/
Settings
\
src
/
Terrain
\
src
/
Terrain
\
src
/
Vehicle
Setup
\
src
/
Vehicle
\
src
/
ViewWidgets
\
src
/
ViewWidgets
\
src
/
Audio
\
src
/
Audio
\
src
/
comm
\
src
/
comm
\
...
@@ -663,7 +663,13 @@ HEADERS += \
...
@@ -663,7 +663,13 @@ HEADERS += \
src
/
SHPFileHelper
.
h
\
src
/
SHPFileHelper
.
h
\
src
/
Terrain
/
TerrainQuery
.
h
\
src
/
Terrain
/
TerrainQuery
.
h
\
src
/
TerrainTile
.
h
\
src
/
TerrainTile
.
h
\
src
/
Vehicle
/
ADSBVehicle
.
h
\
src
/
Vehicle
/
GPSRTKFactGroup
.
h
\
src
/
Vehicle
/
MAVLinkLogManager
.
h
\
src
/
Vehicle
/
MAVLinkLogManager
.
h
\
src
/
Vehicle
/
MultiVehicleManager
.
h
\
src
/
Vehicle
/
TrajectoryPoints
.
h
\
src
/
Vehicle
/
Vehicle
.
h
\
src
/
Vehicle
/
VehicleObjectAvoidance
.
h
\
src
/
VehicleSetup
/
JoystickConfigController
.
h
\
src
/
VehicleSetup
/
JoystickConfigController
.
h
\
src
/
comm
/
LinkConfiguration
.
h
\
src
/
comm
/
LinkConfiguration
.
h
\
src
/
comm
/
LinkInterface
.
h
\
src
/
comm
/
LinkInterface
.
h
\
...
@@ -881,7 +887,13 @@ SOURCES += \
...
@@ -881,7 +887,13 @@ SOURCES += \
src
/
SHPFileHelper
.
cc
\
src
/
SHPFileHelper
.
cc
\
src
/
Terrain
/
TerrainQuery
.
cc
\
src
/
Terrain
/
TerrainQuery
.
cc
\
src
/
TerrainTile
.
cc
\
src
/
TerrainTile
.
cc
\
src
/
Vehicle
/
ADSBVehicle
.
cc
\
src
/
Vehicle
/
GPSRTKFactGroup
.
cc
\
src
/
Vehicle
/
MAVLinkLogManager
.
cc
\
src
/
Vehicle
/
MAVLinkLogManager
.
cc
\
src
/
Vehicle
/
MultiVehicleManager
.
cc
\
src
/
Vehicle
/
TrajectoryPoints
.
cc
\
src
/
Vehicle
/
Vehicle
.
cc
\
src
/
Vehicle
/
VehicleObjectAvoidance
.
cc
\
src
/
VehicleSetup
/
JoystickConfigController
.
cc
\
src
/
VehicleSetup
/
JoystickConfigController
.
cc
\
src
/
comm
/
LinkConfiguration
.
cc
\
src
/
comm
/
LinkConfiguration
.
cc
\
src
/
comm
/
LinkInterface
.
cc
\
src
/
comm
/
LinkInterface
.
cc
\
...
@@ -983,7 +995,6 @@ SOURCES += \
...
@@ -983,7 +995,6 @@ SOURCES += \
INCLUDEPATH
+=
\
INCLUDEPATH
+=
\
src
/
AutoPilotPlugins
/
Common
\
src
/
AutoPilotPlugins
/
Common
\
src
/
FirmwarePlugin
\
src
/
FirmwarePlugin
\
src
/
Vehicle
\
src
/
VehicleSetup
\
src
/
VehicleSetup
\
HEADERS
+=
\
HEADERS
+=
\
...
@@ -998,11 +1009,6 @@ HEADERS+= \
...
@@ -998,11 +1009,6 @@ HEADERS+= \
src
/
FirmwarePlugin
/
CameraMetaData
.
h
\
src
/
FirmwarePlugin
/
CameraMetaData
.
h
\
src
/
FirmwarePlugin
/
FirmwarePlugin
.
h
\
src
/
FirmwarePlugin
/
FirmwarePlugin
.
h
\
src
/
FirmwarePlugin
/
FirmwarePluginManager
.
h
\
src
/
FirmwarePlugin
/
FirmwarePluginManager
.
h
\
src
/
Vehicle
/
ADSBVehicle
.
h
\
src
/
Vehicle
/
MultiVehicleManager
.
h
\
src
/
Vehicle
/
GPSRTKFactGroup
.
h
\
src
/
Vehicle
/
Vehicle
.
h
\
src
/
Vehicle
/
VehicleObjectAvoidance
.
h
\
src
/
VehicleSetup
/
VehicleComponent
.
h
\
src
/
VehicleSetup
/
VehicleComponent
.
h
\
!
MobileBuild
{
!
NoSerialBuild
{
!
MobileBuild
{
!
NoSerialBuild
{
...
@@ -1025,11 +1031,6 @@ SOURCES += \
...
@@ -1025,11 +1031,6 @@ SOURCES += \
src
/
FirmwarePlugin
/
CameraMetaData
.
cc
\
src
/
FirmwarePlugin
/
CameraMetaData
.
cc
\
src
/
FirmwarePlugin
/
FirmwarePlugin
.
cc
\
src
/
FirmwarePlugin
/
FirmwarePlugin
.
cc
\
src
/
FirmwarePlugin
/
FirmwarePluginManager
.
cc
\
src
/
FirmwarePlugin
/
FirmwarePluginManager
.
cc
\
src
/
Vehicle
/
ADSBVehicle
.
cc
\
src
/
Vehicle
/
MultiVehicleManager
.
cc
\
src
/
Vehicle
/
GPSRTKFactGroup
.
cc
\
src
/
Vehicle
/
Vehicle
.
cc
\
src
/
Vehicle
/
VehicleObjectAvoidance
.
cc
\
src
/
VehicleSetup
/
VehicleComponent
.
cc
\
src
/
VehicleSetup
/
VehicleComponent
.
cc
\
!
MobileBuild
{
!
NoSerialBuild
{
!
MobileBuild
{
!
NoSerialBuild
{
...
...
This diff is collapsed.
Click to expand it.
src/FlightDisplay/FlightDisplayViewMap.qml
View file @
00e404d0
...
@@ -49,6 +49,7 @@ FlightMap {
...
@@ -49,6 +49,7 @@ FlightMap {
property
var
_geoFenceController
:
missionController
.
geoFenceController
property
var
_geoFenceController
:
missionController
.
geoFenceController
property
var
_rallyPointController
:
missionController
.
rallyPointController
property
var
_rallyPointController
:
missionController
.
rallyPointController
property
var
activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
property
var
_activeVehicleCoordinate
:
activeVehicle
?
activeVehicle
.
coordinate
:
QtPositioning
.
coordinate
()
property
var
_activeVehicleCoordinate
:
activeVehicle
?
activeVehicle
.
coordinate
:
QtPositioning
.
coordinate
()
property
real
_toolButtonTopMargin
:
parent
.
height
-
mainWindow
.
height
+
(
ScreenTools
.
defaultFontPixelHeight
/
2
)
property
real
_toolButtonTopMargin
:
parent
.
height
-
mainWindow
.
height
+
(
ScreenTools
.
defaultFontPixelHeight
/
2
)
property
bool
_airspaceEnabled
:
QGroundControl
.
airmapSupported
?
(
QGroundControl
.
settingsManager
.
airMapSettings
.
enableAirMap
.
rawValue
&&
QGroundControl
.
airspaceManager
.
connected
):
false
property
bool
_airspaceEnabled
:
QGroundControl
.
airmapSupported
?
(
QGroundControl
.
settingsManager
.
airMapSettings
.
enableAirMap
.
rawValue
&&
QGroundControl
.
airspaceManager
.
connected
):
false
...
@@ -183,17 +184,24 @@ FlightMap {
...
@@ -183,17 +184,24 @@ FlightMap {
property
real
leftToolWidth
:
toolStrip
.
x
+
toolStrip
.
width
property
real
leftToolWidth
:
toolStrip
.
x
+
toolStrip
.
width
}
}
// Add trajectory points to the map
// Add trajectory lines to the map
MapItemView
{
MapPolyline
{
model
:
mainIsMap
?
activeVehicle
?
activeVehicle
.
trajectoryPoints
:
0
:
0
id
:
trajectoryPolyline
delegate
:
MapPolyline
{
line.width
:
3
line.width
:
3
line.color
:
"
red
"
line.color
:
"
red
"
z
:
QGroundControl
.
zOrderTrajectoryLines
z
:
QGroundControl
.
zOrderTrajectoryLines
visible
:
true
//mainIsMap
path
:
[
object
.
coordinate1
,
Connections
{
object
.
coordinate2
,
target
:
QGroundControl
.
multiVehicleManager
]
onActiveVehicleChanged
:
trajectoryPolyline
.
path
=
activeVehicle
?
activeVehicle
.
trajectoryPoints
.
list
()
:
[]
}
Connections
{
target
:
activeVehicle
?
activeVehicle
.
trajectoryPoints
:
null
onPointAdded
:
trajectoryPolyline
.
addCoordinate
(
coordinate
)
onUpdateLastPoint
:
trajectoryPolyline
.
replaceCoordinate
(
trajectoryPolyline
.
pathLength
()
-
1
,
coordinate
)
onPointsCleared
:
trajectoryPolyline
.
path
=
[]
}
}
}
}
...
...
This diff is collapsed.
Click to expand it.
src/QGCApplication.cc
View file @
00e404d0
...
@@ -96,6 +96,7 @@
...
@@ -96,6 +96,7 @@
#include "GeoTagController.h"
#include "GeoTagController.h"
#include "LogReplayLink.h"
#include "LogReplayLink.h"
#include "VehicleObjectAvoidance.h"
#include "VehicleObjectAvoidance.h"
#include "TrajectoryPoints.h"
#if defined(QGC_ENABLE_PAIRING)
#if defined(QGC_ENABLE_PAIRING)
#include "PairingManager.h"
#include "PairingManager.h"
...
@@ -510,6 +511,7 @@ void QGCApplication::_initCommon()
...
@@ -510,6 +511,7 @@ void QGCApplication::_initCommon()
qmlRegisterUncreatableType
<
QGCMapPolygon
>
(
"QGroundControl.FlightMap"
,
1
,
0
,
"QGCMapPolygon"
,
kRefOnly
);
qmlRegisterUncreatableType
<
QGCMapPolygon
>
(
"QGroundControl.FlightMap"
,
1
,
0
,
"QGCMapPolygon"
,
kRefOnly
);
qmlRegisterUncreatableType
<
QGCGeoBoundingCube
>
(
"QGroundControl.FlightMap"
,
1
,
0
,
"QGCGeoBoundingCube"
,
kRefOnly
);
qmlRegisterUncreatableType
<
QGCGeoBoundingCube
>
(
"QGroundControl.FlightMap"
,
1
,
0
,
"QGCGeoBoundingCube"
,
kRefOnly
);
qmlRegisterUncreatableType
<
TrajectoryPoints
>
(
"QGroundControl.FlightMap"
,
1
,
0
,
"TrajectoryPoints"
,
kRefOnly
);
qmlRegisterType
<
QGCMapCircle
>
(
"QGroundControl.FlightMap"
,
1
,
0
,
"QGCMapCircle"
);
qmlRegisterType
<
QGCMapCircle
>
(
"QGroundControl.FlightMap"
,
1
,
0
,
"QGCMapCircle"
);
...
...
This diff is collapsed.
Click to expand it.
src/Vehicle/TrajectoryPoints.cc
0 → 100644
View file @
00e404d0
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "TrajectoryPoints.h"
#include "Vehicle.h"
TrajectoryPoints
::
TrajectoryPoints
(
Vehicle
*
vehicle
,
QObject
*
parent
)
:
QObject
(
parent
)
,
_vehicle
(
vehicle
)
,
_lastAzimuth
(
qQNaN
())
{
}
void
TrajectoryPoints
::
_vehicleCoordinateChanged
(
QGeoCoordinate
coordinate
)
{
if
(
_lastPoint
.
isValid
())
{
if
(
_lastPoint
.
distanceTo
(
coordinate
)
>
_distanceTolerance
)
{
double
newAzimuth
=
_lastPoint
.
azimuthTo
(
coordinate
);
if
(
qIsNaN
(
_lastAzimuth
)
||
qAbs
(
newAzimuth
-
_lastAzimuth
)
>
_azimuthTolerance
)
{
_lastAzimuth
=
_lastPoint
.
azimuthTo
(
coordinate
);
_lastPoint
=
coordinate
;
_points
.
append
(
QVariant
::
fromValue
(
coordinate
));
emit
pointAdded
(
coordinate
);
}
else
{
_lastPoint
=
coordinate
;
_points
[
_points
.
count
()
-
1
]
=
QVariant
::
fromValue
(
coordinate
);
emit
updateLastPoint
(
coordinate
);
}
}
}
else
{
_lastAzimuth
=
_lastPoint
.
azimuthTo
(
coordinate
);
_lastPoint
=
coordinate
;
_points
.
append
(
QVariant
::
fromValue
(
coordinate
));
emit
pointAdded
(
coordinate
);
}
}
void
TrajectoryPoints
::
start
(
void
)
{
clear
();
connect
(
_vehicle
,
&
Vehicle
::
coordinateChanged
,
this
,
&
TrajectoryPoints
::
_vehicleCoordinateChanged
);
}
void
TrajectoryPoints
::
stop
(
void
)
{
qDebug
()
<<
"Stop"
<<
_points
.
count
();
disconnect
(
_vehicle
,
&
Vehicle
::
coordinateChanged
,
this
,
&
TrajectoryPoints
::
_vehicleCoordinateChanged
);
}
void
TrajectoryPoints
::
clear
(
void
)
{
_points
.
clear
();
emit
pointsCleared
();
}
This diff is collapsed.
Click to expand it.
src/Vehicle/TrajectoryPoints.h
0 → 100644
View file @
00e404d0
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "QmlObjectListModel.h"
#include <QGeoCoordinate>
class
Vehicle
;
class
TrajectoryPoints
:
public
QObject
{
Q_OBJECT
public:
TrajectoryPoints
(
Vehicle
*
vehicle
,
QObject
*
parent
=
nullptr
);
Q_INVOKABLE
QVariantList
list
(
void
)
const
{
return
_points
;
}
void
start
(
void
);
void
stop
(
void
);
public
slots
:
void
clear
(
void
);
signals:
void
pointAdded
(
QGeoCoordinate
coordinate
);
void
updateLastPoint
(
QGeoCoordinate
coordinate
);
void
pointsCleared
(
void
);
private
slots
:
void
_vehicleCoordinateChanged
(
QGeoCoordinate
coordinate
);
private:
Vehicle
*
_vehicle
;
QVariantList
_points
;
QGeoCoordinate
_lastPoint
;
double
_lastAzimuth
;
static
constexpr
double
_distanceTolerance
=
2
.
0
;
static
constexpr
double
_azimuthTolerance
=
1
.
5
;
};
This diff is collapsed.
Click to expand it.
src/Vehicle/Vehicle.cc
View file @
00e404d0
...
@@ -41,6 +41,7 @@
...
@@ -41,6 +41,7 @@
#include "VideoSettings.h"
#include "VideoSettings.h"
#include "PositionManager.h"
#include "PositionManager.h"
#include "VehicleObjectAvoidance.h"
#include "VehicleObjectAvoidance.h"
#include "TrajectoryPoints.h"
#if defined(QGC_AIRMAP_ENABLED)
#if defined(QGC_AIRMAP_ENABLED)
#include "AirspaceVehicleManager.h"
#include "AirspaceVehicleManager.h"
...
@@ -166,6 +167,7 @@ Vehicle::Vehicle(LinkInterface* link,
...
@@ -166,6 +167,7 @@ Vehicle::Vehicle(LinkInterface* link,
,
_base_mode
(
0
)
,
_base_mode
(
0
)
,
_custom_mode
(
0
)
,
_custom_mode
(
0
)
,
_nextSendMessageMultipleIndex
(
0
)
,
_nextSendMessageMultipleIndex
(
0
)
,
_trajectoryPoints
(
new
TrajectoryPoints
(
this
,
this
))
,
_firmwarePluginManager
(
firmwarePluginManager
)
,
_firmwarePluginManager
(
firmwarePluginManager
)
,
_joystickManager
(
joystickManager
)
,
_joystickManager
(
joystickManager
)
,
_flowImageIndex
(
0
)
,
_flowImageIndex
(
0
)
...
@@ -287,9 +289,6 @@ Vehicle::Vehicle(LinkInterface* link,
...
@@ -287,9 +289,6 @@ Vehicle::Vehicle(LinkInterface* link,
_sendMultipleTimer
.
start
(
_sendMessageMultipleIntraMessageDelay
);
_sendMultipleTimer
.
start
(
_sendMessageMultipleIntraMessageDelay
);
connect
(
&
_sendMultipleTimer
,
&
QTimer
::
timeout
,
this
,
&
Vehicle
::
_sendMessageMultipleNext
);
connect
(
&
_sendMultipleTimer
,
&
QTimer
::
timeout
,
this
,
&
Vehicle
::
_sendMessageMultipleNext
);
_mapTrajectoryTimer
.
setInterval
(
_mapTrajectoryMsecsBetweenPoints
);
connect
(
&
_mapTrajectoryTimer
,
&
QTimer
::
timeout
,
this
,
&
Vehicle
::
_addNewMapTrajectoryPoint
);
connect
(
&
_orbitTelemetryTimer
,
&
QTimer
::
timeout
,
this
,
&
Vehicle
::
_orbitTelemetryTimeout
);
connect
(
&
_orbitTelemetryTimer
,
&
QTimer
::
timeout
,
this
,
&
Vehicle
::
_orbitTelemetryTimeout
);
// Create camera manager instance
// Create camera manager instance
...
@@ -373,6 +372,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
...
@@ -373,6 +372,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
,
_base_mode
(
0
)
,
_base_mode
(
0
)
,
_custom_mode
(
0
)
,
_custom_mode
(
0
)
,
_nextSendMessageMultipleIndex
(
0
)
,
_nextSendMessageMultipleIndex
(
0
)
,
_trajectoryPoints
(
new
TrajectoryPoints
(
this
,
this
))
,
_firmwarePluginManager
(
firmwarePluginManager
)
,
_firmwarePluginManager
(
firmwarePluginManager
)
,
_joystickManager
(
nullptr
)
,
_joystickManager
(
nullptr
)
,
_flowImageIndex
(
0
)
,
_flowImageIndex
(
0
)
...
@@ -445,18 +445,18 @@ void Vehicle::_commonInit(void)
...
@@ -445,18 +445,18 @@ 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
);
connect
(
_missionManager
,
&
MissionManager
::
error
,
this
,
&
Vehicle
::
_missionManagerError
);
connect
(
_missionManager
,
&
MissionManager
::
error
,
this
,
&
Vehicle
::
_missionManagerError
);
connect
(
_missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
Vehicle
::
_missionLoadComplete
);
connect
(
_missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
Vehicle
::
_missionLoadComplete
);
connect
(
_missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
Vehicle
::
_clearCameraTriggerPoints
);
connect
(
_missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
Vehicle
::
_clearCameraTriggerPoints
);
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
::
currentIndexChanged
,
this
,
&
Vehicle
::
_updateHeadingToNextWP
);
connect
(
_missionManager
,
&
MissionManager
::
currentIndexChanged
,
this
,
&
Vehicle
::
_updateHeadingToNextWP
);
connect
(
_missionManager
,
&
MissionManager
::
sendComplete
,
_trajectoryPoints
,
&
TrajectoryPoints
::
clear
);
connect
(
_missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
_trajectoryPoints
,
&
TrajectoryPoints
::
clear
);
_parameterManager
=
new
ParameterManager
(
this
);
_parameterManager
=
new
ParameterManager
(
this
);
connect
(
_parameterManager
,
&
ParameterManager
::
parametersReadyChanged
,
this
,
&
Vehicle
::
_parametersReady
);
connect
(
_parameterManager
,
&
ParameterManager
::
parametersReadyChanged
,
this
,
&
Vehicle
::
_parametersReady
);
...
@@ -520,6 +520,9 @@ void Vehicle::_commonInit(void)
...
@@ -520,6 +520,9 @@ void Vehicle::_commonInit(void)
_flightDistanceFact
.
setRawValue
(
0
);
_flightDistanceFact
.
setRawValue
(
0
);
_flightTimeFact
.
setRawValue
(
0
);
_flightTimeFact
.
setRawValue
(
0
);
_flightTimeUpdater
.
setInterval
(
1000
);
_flightTimeUpdater
.
setSingleShot
(
false
);
connect
(
&
_flightTimeUpdater
,
&
QTimer
::
timeout
,
this
,
&
Vehicle
::
_updateFlightTime
);
// Set video stream to udp if running ArduSub and Video is disabled
// Set video stream to udp if running ArduSub and Video is disabled
if
(
sub
()
&&
_settingsManager
->
videoSettings
()
->
videoSource
()
->
rawValue
()
==
VideoSettings
::
videoDisabled
)
{
if
(
sub
()
&&
_settingsManager
->
videoSettings
()
->
videoSource
()
->
rawValue
()
==
VideoSettings
::
videoDisabled
)
{
...
@@ -1657,10 +1660,12 @@ void Vehicle::_updateArmed(bool armed)
...
@@ -1657,10 +1660,12 @@ void Vehicle::_updateArmed(bool armed)
// We are transitioning to the armed state, begin tracking trajectory points for the map
// We are transitioning to the armed state, begin tracking trajectory points for the map
if
(
_armed
)
{
if
(
_armed
)
{
_mapTrajectoryStart
();
_trajectoryPoints
->
start
();
_flightTimerStart
();
_clearCameraTriggerPoints
();
_clearCameraTriggerPoints
();
}
else
{
}
else
{
_mapTrajectoryStop
();
_trajectoryPoints
->
stop
();
_flightTimerStop
();
// Also handle Video Streaming
// Also handle Video Streaming
if
(
qgcApp
()
->
toolbox
()
->
videoManager
()
->
videoReceiver
())
{
if
(
qgcApp
()
->
toolbox
()
->
videoManager
()
->
videoReceiver
())
{
if
(
_settingsManager
->
videoSettings
()
->
disableWhenDisarmed
()
->
rawValue
().
toBool
())
{
if
(
_settingsManager
->
videoSettings
()
->
disableWhenDisarmed
()
->
rawValue
().
toBool
())
{
...
@@ -2546,46 +2551,27 @@ void Vehicle::_rallyPointManagerError(int errorCode, const QString& errorMsg)
...
@@ -2546,46 +2551,27 @@ void Vehicle::_rallyPointManagerError(int errorCode, const QString& errorMsg)
qgcApp
()
->
showMessage
(
tr
(
"Rally Point transfer failed. Retry transfer. Error: %1"
).
arg
(
errorMsg
));
qgcApp
()
->
showMessage
(
tr
(
"Rally Point transfer failed. Retry transfer. Error: %1"
).
arg
(
errorMsg
));
}
}
void
Vehicle
::
_addNewMapTrajectoryPoint
(
void
)
{
if
(
_mapTrajectoryHaveFirstCoordinate
)
{
// Keep three minutes of trajectory on mobile due to perf impact of lines
#ifdef __mobile__
if
(
_mapTrajectoryList
.
count
()
*
_mapTrajectoryMsecsBetweenPoints
>
3
*
1000
*
60
)
{
_mapTrajectoryList
.
removeAt
(
0
)
->
deleteLater
();
}
#endif
_mapTrajectoryList
.
append
(
new
CoordinateVector
(
_mapTrajectoryLastCoordinate
,
_coordinate
,
this
));
_flightDistanceFact
.
setRawValue
(
_flightDistanceFact
.
rawValue
().
toDouble
()
+
_mapTrajectoryLastCoordinate
.
distanceTo
(
_coordinate
));
}
_mapTrajectoryHaveFirstCoordinate
=
true
;
_mapTrajectoryLastCoordinate
=
_coordinate
;
_flightTimeFact
.
setRawValue
((
double
)
_flightTimer
.
elapsed
()
/
1000.0
);
}
void
Vehicle
::
_clearTrajectoryPoints
(
void
)
{
_mapTrajectoryList
.
clearAndDeleteContents
();
}
void
Vehicle
::
_clearCameraTriggerPoints
(
void
)
void
Vehicle
::
_clearCameraTriggerPoints
(
void
)
{
{
_cameraTriggerPoints
.
clearAndDeleteContents
();
_cameraTriggerPoints
.
clearAndDeleteContents
();
}
}
void
Vehicle
::
_
mapTrajectory
Start
(
void
)
void
Vehicle
::
_
flightTimer
Start
(
void
)
{
{
_mapTrajectoryHaveFirstCoordinate
=
false
;
_clearTrajectoryPoints
();
_mapTrajectoryTimer
.
start
();
_flightTimer
.
start
();
_flightTimer
.
start
();
_flightTimeUpdater
.
start
();
_flightDistanceFact
.
setRawValue
(
0
);
_flightDistanceFact
.
setRawValue
(
0
);
_flightTimeFact
.
setRawValue
(
0
);
_flightTimeFact
.
setRawValue
(
0
);
}
}
void
Vehicle
::
_
mapTrajectoryStop
(
)
void
Vehicle
::
_
flightTimerStop
(
void
)
{
{
_mapTrajectoryTimer
.
stop
();
_flightTimeUpdater
.
stop
();
}
void
Vehicle
::
_updateFlightTime
(
void
)
{
_flightTimeFact
.
setRawValue
((
double
)
_flightTimer
.
elapsed
()
/
1000.0
);
}
}
void
Vehicle
::
_startPlanRequest
(
void
)
void
Vehicle
::
_startPlanRequest
(
void
)
...
...
This diff is collapsed.
Click to expand it.
src/Vehicle/Vehicle.h
View file @
00e404d0
...
@@ -38,6 +38,7 @@ class ADSBVehicle;
...
@@ -38,6 +38,7 @@ class ADSBVehicle;
class
QGCCameraManager
;
class
QGCCameraManager
;
class
Joystick
;
class
Joystick
;
class
VehicleObjectAvoidance
;
class
VehicleObjectAvoidance
;
class
TrajectoryPoints
;
#if defined(QGC_AIRMAP_ENABLED)
#if defined(QGC_AIRMAP_ENABLED)
class
AirspaceVehicleManager
;
class
AirspaceVehicleManager
;
...
@@ -548,7 +549,7 @@ public:
...
@@ -548,7 +549,7 @@ public:
Q_PROPERTY
(
QStringList
flightModes
READ
flightModes
NOTIFY
flightModesChanged
)
Q_PROPERTY
(
QStringList
flightModes
READ
flightModes
NOTIFY
flightModesChanged
)
Q_PROPERTY
(
QString
flightMode
READ
flightMode
WRITE
setFlightMode
NOTIFY
flightModeChanged
)
Q_PROPERTY
(
QString
flightMode
READ
flightMode
WRITE
setFlightMode
NOTIFY
flightModeChanged
)
Q_PROPERTY
(
bool
hilMode
READ
hilMode
WRITE
setHilMode
NOTIFY
hilModeChanged
)
Q_PROPERTY
(
bool
hilMode
READ
hilMode
WRITE
setHilMode
NOTIFY
hilModeChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
trajectoryPoints
READ
trajectoryPoints
CONSTANT
)
Q_PROPERTY
(
TrajectoryPoints
*
trajectoryPoints
MEMBER
_trajectoryPoints
CONSTANT
)
Q_PROPERTY
(
QmlObjectListModel
*
cameraTriggerPoints
READ
cameraTriggerPoints
CONSTANT
)
Q_PROPERTY
(
QmlObjectListModel
*
cameraTriggerPoints
READ
cameraTriggerPoints
CONSTANT
)
Q_PROPERTY
(
float
latitude
READ
latitude
NOTIFY
coordinateChanged
)
Q_PROPERTY
(
float
latitude
READ
latitude
NOTIFY
coordinateChanged
)
Q_PROPERTY
(
float
longitude
READ
longitude
NOTIFY
coordinateChanged
)
Q_PROPERTY
(
float
longitude
READ
longitude
NOTIFY
coordinateChanged
)
...
@@ -878,9 +879,8 @@ public:
...
@@ -878,9 +879,8 @@ public:
QString
prearmError
(
void
)
const
{
return
_prearmError
;
}
QString
prearmError
(
void
)
const
{
return
_prearmError
;
}
void
setPrearmError
(
const
QString
&
prearmError
);
void
setPrearmError
(
const
QString
&
prearmError
);
QmlObjectListModel
*
trajectoryPoints
(
void
)
{
return
&
_mapTrajectoryList
;
}
QmlObjectListModel
*
cameraTriggerPoints
(
void
)
{
return
&
_cameraTriggerPoints
;
}
QmlObjectListModel
*
cameraTriggerPoints
(
void
)
{
return
&
_cameraTriggerPoints
;
}
QmlObjectListModel
*
adsbVehicles
(
void
)
{
return
&
_adsbVehicles
;
}
QmlObjectListModel
*
adsbVehicles
(
void
)
{
return
&
_adsbVehicles
;
}
int
flowImageIndex
()
{
return
_flowImageIndex
;
}
int
flowImageIndex
()
{
return
_flowImageIndex
;
}
...
@@ -1228,7 +1228,6 @@ private slots:
...
@@ -1228,7 +1228,6 @@ private slots:
void
_linkInactiveOrDeleted
(
LinkInterface
*
link
);
void
_linkInactiveOrDeleted
(
LinkInterface
*
link
);
void
_sendMessageOnLink
(
LinkInterface
*
link
,
mavlink_message_t
message
);
void
_sendMessageOnLink
(
LinkInterface
*
link
,
mavlink_message_t
message
);
void
_sendMessageMultipleNext
(
void
);
void
_sendMessageMultipleNext
(
void
);
void
_addNewMapTrajectoryPoint
(
void
);
void
_parametersReady
(
bool
parametersReady
);
void
_parametersReady
(
bool
parametersReady
);
void
_remoteControlRSSIChanged
(
uint8_t
rssi
);
void
_remoteControlRSSIChanged
(
uint8_t
rssi
);
void
_handleFlightModeChanged
(
const
QString
&
flightMode
);
void
_handleFlightModeChanged
(
const
QString
&
flightMode
);
...
@@ -1248,7 +1247,6 @@ private slots:
...
@@ -1248,7 +1247,6 @@ private slots:
void
_geoFenceLoadComplete
(
void
);
void
_geoFenceLoadComplete
(
void
);
void
_rallyPointLoadComplete
(
void
);
void
_rallyPointLoadComplete
(
void
);
void
_sendMavCommandAgain
(
void
);
void
_sendMavCommandAgain
(
void
);
void
_clearTrajectoryPoints
(
void
);
void
_clearCameraTriggerPoints
(
void
);
void
_clearCameraTriggerPoints
(
void
);
void
_updateDistanceHeadingToHome
(
void
);
void
_updateDistanceHeadingToHome
(
void
);
void
_updateHeadingToNextWP
(
void
);
void
_updateHeadingToNextWP
(
void
);
...
@@ -1262,6 +1260,7 @@ private slots:
...
@@ -1262,6 +1260,7 @@ private slots:
void
_adsbTimerTimeout
();
void
_adsbTimerTimeout
();
void
_orbitTelemetryTimeout
(
void
);
void
_orbitTelemetryTimeout
(
void
);
void
_protocolVersionTimeOut
(
void
);
void
_protocolVersionTimeOut
(
void
);
void
_updateFlightTime
(
void
);
private:
private:
bool
_containsLink
(
LinkInterface
*
link
);
bool
_containsLink
(
LinkInterface
*
link
);
...
@@ -1315,8 +1314,6 @@ private:
...
@@ -1315,8 +1314,6 @@ private:
void
_missionManagerError
(
int
errorCode
,
const
QString
&
errorMsg
);
void
_missionManagerError
(
int
errorCode
,
const
QString
&
errorMsg
);
void
_geoFenceManagerError
(
int
errorCode
,
const
QString
&
errorMsg
);
void
_geoFenceManagerError
(
int
errorCode
,
const
QString
&
errorMsg
);
void
_rallyPointManagerError
(
int
errorCode
,
const
QString
&
errorMsg
);
void
_rallyPointManagerError
(
int
errorCode
,
const
QString
&
errorMsg
);
void
_mapTrajectoryStart
(
void
);
void
_mapTrajectoryStop
(
void
);
void
_linkActiveChanged
(
LinkInterface
*
link
,
bool
active
,
int
vehicleID
);
void
_linkActiveChanged
(
LinkInterface
*
link
,
bool
active
,
int
vehicleID
);
void
_say
(
const
QString
&
text
);
void
_say
(
const
QString
&
text
);
QString
_vehicleIdSpeech
(
void
);
QString
_vehicleIdSpeech
(
void
);
...
@@ -1336,6 +1333,8 @@ private:
...
@@ -1336,6 +1333,8 @@ private:
void
_handleUnsupportedRequestProtocolVersion
(
void
);
void
_handleUnsupportedRequestProtocolVersion
(
void
);
void
_initializeCsv
();
void
_initializeCsv
();
void
_writeCsvLine
();
void
_writeCsvLine
();
void
_flightTimerStart
(
void
);
void
_flightTimerStop
(
void
);
int
_id
;
///< Mavlink system id
int
_id
;
///< Mavlink system id
int
_defaultComponentId
;
int
_defaultComponentId
;
...
@@ -1465,15 +1464,10 @@ private:
...
@@ -1465,15 +1464,10 @@ private:
QTimer
_sendMultipleTimer
;
QTimer
_sendMultipleTimer
;
int
_nextSendMessageMultipleIndex
;
int
_nextSendMessageMultipleIndex
;
QTime
_flightTimer
;
QTime
_flightTimer
;
QTimer
_mapTrajectoryTimer
;
QTimer
_flightTimeUpdater
;
QmlObjectListModel
_mapTrajectoryList
;
TrajectoryPoints
*
_trajectoryPoints
;
QGeoCoordinate
_mapTrajectoryLastCoordinate
;
QmlObjectListModel
_cameraTriggerPoints
;
bool
_mapTrajectoryHaveFirstCoordinate
;
static
const
int
_mapTrajectoryMsecsBetweenPoints
=
1000
;
QmlObjectListModel
_cameraTriggerPoints
;
QmlObjectListModel
_adsbVehicles
;
QmlObjectListModel
_adsbVehicles
;
QMap
<
uint32_t
,
ADSBVehicle
*>
_adsbICAOMap
;
QMap
<
uint32_t
,
ADSBVehicle
*>
_adsbICAOMap
;
QMap
<
QString
,
ADSBVehicle
*>
_trafficVehicleMap
;
QMap
<
QString
,
ADSBVehicle
*>
_trafficVehicleMap
;
...
...
This diff is collapsed.
Click to expand it.
src/uas/UASMessageHandler.h
View file @
00e404d0
...
@@ -7,20 +7,12 @@
...
@@ -7,20 +7,12 @@
*
*
****************************************************************************/
****************************************************************************/
/*!
* @file
* @brief Message Handler
* @author Gus Grubba <mavlink@grubba.com>
*/
#pragma once
#pragma once
#include <QObject>
#include <QObject>
#include <QVector>
#include <QVector>
#include <QMutex>
#include <QMutex>
#include "Vehicle.h"
#include "QGCToolbox.h"
#include "QGCToolbox.h"
class
Vehicle
;
class
Vehicle
;
...
...
This diff is collapsed.
Click to expand it.
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