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
1e0e8d4d
Commit
1e0e8d4d
authored
Mar 22, 2017
by
Don Gagne
Committed by
GitHub
Mar 22, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #4818 from DonLakeFlyer/MapGimbalYaw
Show gimbal yaw on map
parents
5d39fa57
62d7bd4c
Changes
22
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
22 changed files
with
446 additions
and
283 deletions
+446
-283
MissionItemIndicator.qml
src/FlightMap/MapItems/MissionItemIndicator.qml
+7
-4
SimpleItemMapVisual.qml
src/MissionEditor/SimpleItemMapVisual.qml
+1
-1
CameraSection.cc
src/MissionManager/CameraSection.cc
+12
-0
CameraSection.h
src/MissionManager/CameraSection.h
+5
-0
ComplexMissionItem.h
src/MissionManager/ComplexMissionItem.h
+0
-3
FixedWingLandingComplexItem.cc
src/MissionManager/FixedWingLandingComplexItem.cc
+0
-6
FixedWingLandingComplexItem.h
src/MissionManager/FixedWingLandingComplexItem.h
+2
-2
MissionController.cc
src/MissionManager/MissionController.cc
+165
-121
MissionController.h
src/MissionManager/MissionController.h
+33
-31
MissionItem.cc
src/MissionManager/MissionItem.cc
+30
-3
MissionItem.h
src/MissionManager/MissionItem.h
+10
-5
MissionSettingsComplexItem.cc
src/MissionManager/MissionSettingsComplexItem.cc
+14
-6
MissionSettingsComplexItem.h
src/MissionManager/MissionSettingsComplexItem.h
+6
-6
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+12
-4
SimpleMissionItem.h
src/MissionManager/SimpleMissionItem.h
+2
-1
SurveyMissionItem.cc
src/MissionManager/SurveyMissionItem.cc
+4
-9
SurveyMissionItem.h
src/MissionManager/SurveyMissionItem.h
+3
-2
VisualMissionItem.cc
src/MissionManager/VisualMissionItem.cc
+19
-0
VisualMissionItem.h
src/MissionManager/VisualMissionItem.h
+46
-44
MissionItemIndexLabel.qml
src/QmlControls/MissionItemIndexLabel.qml
+61
-21
Vehicle.cc
src/Vehicle/Vehicle.cc
+8
-8
Vehicle.h
src/Vehicle/Vehicle.h
+6
-6
No files found.
src/FlightMap/MapItems/MissionItemIndicator.qml
View file @
1e0e8d4d
...
...
@@ -29,10 +29,13 @@ MapQuickItem {
sourceItem
:
MissionItemIndexLabel
{
id
:
_label
checked
:
_isCurrentItem
label
:
missionItem
?
missionItem
.
abbreviation
:
""
onClicked
:
_item
.
clicked
()
id
:
_label
checked
:
_isCurrentItem
label
:
missionItem
?
missionItem
.
abbreviation
:
""
gimbalYaw
:
missionItem
.
missionGimbalYaw
vehicleYaw
:
missionItem
.
missionVehicleYaw
showGimbalYaw
:
missionItem
.
showMissionGimbalYaw
onClicked
:
_item
.
clicked
()
property
bool
_isCurrentItem
:
missionItem
?
missionItem
.
isCurrentItem
:
false
}
...
...
src/MissionEditor/SimpleItemMapVisual.qml
View file @
1e0e8d4d
...
...
@@ -115,9 +115,9 @@ Item {
model
:
_missionItem
.
childItems
delegate
:
MissionItemIndexLabel
{
z
:
2
label
:
object
.
abbreviation
checked
:
object
.
isCurrentItem
z
:
2
specifiesCoordinate
:
false
onClicked
:
setCurrentItem
(
object
.
sequenceNumber
)
...
...
src/MissionManager/CameraSection.cc
View file @
1e0e8d4d
...
...
@@ -55,6 +55,8 @@ CameraSection::CameraSection(QObject* parent)
connect
(
&
_gimbalYawFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirty
);
connect
(
&
_cameraPhotoIntervalDistanceFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirty
);
connect
(
&
_cameraPhotoIntervalTimeFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirty
);
connect
(
&
_gimbalYawFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_updateSpecifiedGimbalYaw
);
}
void
CameraSection
::
setSpecifyGimbal
(
bool
specifyGimbal
)
...
...
@@ -254,3 +256,13 @@ void CameraSection::setAvailable(bool available)
emit
availableChanged
(
available
);
}
}
double
CameraSection
::
specifiedGimbalYaw
(
void
)
const
{
return
_specifyGimbal
?
_gimbalYawFact
.
rawValue
().
toDouble
()
:
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
CameraSection
::
_updateSpecifiedGimbalYaw
(
void
)
{
emit
specifiedGimbalYawChanged
(
specifiedGimbalYaw
());
}
src/MissionManager/CameraSection.h
View file @
1e0e8d4d
...
...
@@ -49,6 +49,9 @@ public:
Fact
*
cameraPhotoIntervalTime
(
void
)
{
return
&
_cameraPhotoIntervalTimeFact
;
}
Fact
*
cameraPhotoIntervalDistance
(
void
)
{
return
&
_cameraPhotoIntervalDistanceFact
;
}
///< @return The gimbal yaw specified by this item, NaN if not specified
double
specifiedGimbalYaw
(
void
)
const
;
/// Scans the loaded items for the section items
/// @param visualItems Item list
/// @param scanIndex Index to start scanning from
...
...
@@ -75,10 +78,12 @@ signals:
void
dirtyChanged
(
bool
dirty
);
bool
specifyGimbalChanged
(
bool
specifyGimbal
);
void
missionItemCountChanged
(
int
missionItemCount
);
void
specifiedGimbalYawChanged
(
double
gimbalYaw
);
private
slots
:
void
_setDirty
(
void
);
void
_setDirtyAndUpdateMissionItemCount
(
void
);
void
_updateSpecifiedGimbalYaw
(
void
);
private:
bool
_available
;
...
...
src/MissionManager/ComplexMissionItem.h
View file @
1e0e8d4d
...
...
@@ -38,9 +38,6 @@ public:
/// @return the greatest distance from any point of the complex item to some coordinate
virtual
double
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
=
0
;
/// Informs the complex item of the cruise speed it will fly at
virtual
void
setCruiseSpeed
(
double
cruiseSpeed
)
=
0
;
/// This mission item attribute specifies the type of the complex item.
static
const
char
*
jsonComplexItemTypeKey
;
...
...
src/MissionManager/FixedWingLandingComplexItem.cc
View file @
1e0e8d4d
...
...
@@ -250,12 +250,6 @@ double FixedWingLandingComplexItem::complexDistance(void) const
return
_loiterCoordinate
.
distanceTo
(
_landingCoordinate
);
}
void
FixedWingLandingComplexItem
::
setCruiseSpeed
(
double
cruiseSpeed
)
{
// We don't care about cruise speed
Q_UNUSED
(
cruiseSpeed
);
}
void
FixedWingLandingComplexItem
::
setLandingCoordinate
(
const
QGeoCoordinate
&
coordinate
)
{
if
(
coordinate
!=
_landingCoordinate
)
{
...
...
src/MissionManager/FixedWingLandingComplexItem.h
View file @
1e0e8d4d
...
...
@@ -55,7 +55,6 @@ public:
int
lastSequenceNumber
(
void
)
const
final
;
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
final
;
double
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
final
;
void
setCruiseSpeed
(
double
cruiseSpeed
)
final
;
QString
mapVisualQML
(
void
)
const
final
{
return
QStringLiteral
(
"FWLandingPatternMapVisual.qml"
);
}
// Overrides from VisualMissionItem
...
...
@@ -71,7 +70,8 @@ public:
QGeoCoordinate
coordinate
(
void
)
const
final
{
return
_loiterCoordinate
;
}
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
_landingCoordinate
;
}
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
flightSpeed
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedFlightSpeed
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalYaw
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
bool
coordinateHasRelativeAltitude
(
void
)
const
final
{
return
true
;
}
...
...
src/MissionManager/MissionController.cc
View file @
1e0e8d4d
This diff is collapsed.
Click to expand it.
src/MissionManager/MissionController.h
View file @
1e0e8d4d
...
...
@@ -16,11 +16,11 @@
#include "Vehicle.h"
#include "QGCLoggingCategory.h"
#include "MavlinkQmlSingleton.h"
#include "VisualMissionItem.h"
#include <QHash>
class
CoordinateVector
;
class
VisualMissionItem
;
Q_DECLARE_LOGGING_CATEGORY
(
MissionControllerLog
)
...
...
@@ -34,6 +34,20 @@ public:
MissionController
(
QObject
*
parent
=
NULL
);
~
MissionController
();
typedef
struct
{
double
maxTelemetryDistance
;
double
totalDistance
;
double
totalTime
;
double
hoverDistance
;
double
hoverTime
;
double
cruiseDistance
;
double
cruiseTime
;
double
cruiseSpeed
;
double
hoverSpeed
;
double
vehicleSpeed
;
//</ Either cruise or hover speed based on vehicle type and vtol state
double
gimbalYaw
;
///< NaN signals yaw was never changed
}
MissionFlightStatus_t
;
// Mission settings
Q_PROPERTY
(
QGeoCoordinate
plannedHomePosition
READ
plannedHomePosition
NOTIFY
plannedHomePositionChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
visualItems
READ
visualItems
NOTIFY
visualItemsChanged
)
...
...
@@ -96,15 +110,13 @@ public:
QmlObjectListModel
*
visualItems
(
void
)
{
return
_visualItems
;
}
QmlObjectListModel
*
waypointLines
(
void
)
{
return
&
_waypointLines
;
}
double
missionDistance
(
void
)
const
{
return
_missionDistance
;
}
double
missionTime
(
void
)
const
{
return
_missionTime
;
}
double
missionHoverDistance
(
void
)
const
{
return
_missionHoverDistance
;
}
double
missionHoverTime
(
void
)
const
{
return
_missionHoverTime
;
}
double
missionCruiseDistance
(
void
)
const
{
return
_missionCruiseDistance
;
}
double
missionCruiseTime
(
void
)
const
{
return
_missionCruiseTime
;
}
double
missionMaxTelemetry
(
void
)
const
{
return
_missionMaxTelemetry
;
}
double
cruiseSpeed
(
void
)
const
;
double
hoverSpeed
(
void
)
const
;
double
missionDistance
(
void
)
const
{
return
_missionFlightStatus
.
totalDistance
;
}
double
missionTime
(
void
)
const
{
return
_missionFlightStatus
.
totalTime
;
}
double
missionHoverDistance
(
void
)
const
{
return
_missionFlightStatus
.
hoverDistance
;
}
double
missionHoverTime
(
void
)
const
{
return
_missionFlightStatus
.
hoverTime
;
}
double
missionCruiseDistance
(
void
)
const
{
return
_missionFlightStatus
.
cruiseDistance
;
}
double
missionCruiseTime
(
void
)
const
{
return
_missionFlightStatus
.
cruiseTime
;
}
double
missionMaxTelemetry
(
void
)
const
{
return
_missionFlightStatus
.
maxTelemetryDistance
;
}
signals:
void
plannedHomePositionChanged
(
QGeoCoordinate
plannedHomePosition
);
...
...
@@ -118,10 +130,6 @@ signals:
void
missionCruiseDistanceChanged
(
double
missionCruiseDistance
);
void
missionCruiseTimeChanged
(
void
);
void
missionMaxTelemetryChanged
(
double
missionMaxTelemetry
);
void
cruiseDistanceChanged
(
double
cruiseDistance
);
void
hoverDistanceChanged
(
double
hoverDistance
);
void
cruiseSpeedChanged
(
double
cruiseSpeed
);
void
hoverSpeedChanged
(
double
hoverSpeed
);
private
slots
:
void
_newMissionItemsAvailableFromVehicle
(
bool
removeAllRequested
);
...
...
@@ -131,7 +139,7 @@ private slots:
void
_inProgressChanged
(
bool
inProgress
);
void
_currentMissionItemChanged
(
int
sequenceNumber
);
void
_recalcWaypointLines
(
void
);
void
_recalc
AltitudeRangeBearing
(
void
);
void
_recalc
MissionFlightStatus
(
void
);
void
_homeCoordinateChanged
(
void
);
void
_updateContainsItems
(
void
);
...
...
@@ -170,22 +178,16 @@ private:
void
_activeVehicleSet
(
void
)
final
;
private:
QmlObjectListModel
*
_visualItems
;
QmlObjectListModel
_waypointLines
;
CoordVectHashTable
_linesTable
;
bool
_firstItemsFromVehicle
;
bool
_missionItemsRequested
;
bool
_queuedSend
;
double
_missionDistance
;
double
_missionTime
;
double
_missionHoverDistance
;
double
_missionHoverTime
;
double
_missionCruiseDistance
;
double
_missionCruiseTime
;
double
_missionMaxTelemetry
;
QString
_surveyMissionItemName
;
QString
_fwLandingMissionItemName
;
QStringList
_complexMissionItemNames
;
QmlObjectListModel
*
_visualItems
;
QmlObjectListModel
_waypointLines
;
CoordVectHashTable
_linesTable
;
bool
_firstItemsFromVehicle
;
bool
_missionItemsRequested
;
bool
_queuedSend
;
MissionFlightStatus_t
_missionFlightStatus
;
QString
_surveyMissionItemName
;
QString
_fwLandingMissionItemName
;
QStringList
_complexMissionItemNames
;
static
const
char
*
_settingsGroup
;
...
...
src/MissionManager/MissionItem.cc
View file @
1e0e8d4d
...
...
@@ -53,6 +53,7 @@ MissionItem::MissionItem(QObject* parent)
setAutoContinue
(
true
);
connect
(
&
_param2Fact
,
&
Fact
::
rawValueChanged
,
this
,
&
MissionItem
::
_param2Changed
);
connect
(
&
_param3Fact
,
&
Fact
::
rawValueChanged
,
this
,
&
MissionItem
::
_param3Changed
);
}
MissionItem
::
MissionItem
(
int
sequenceNumber
,
...
...
@@ -99,6 +100,7 @@ MissionItem::MissionItem(int sequenceNumber,
_param7Fact
.
setRawValue
(
param7
);
connect
(
&
_param2Fact
,
&
Fact
::
rawValueChanged
,
this
,
&
MissionItem
::
_param2Changed
);
connect
(
&
_param3Fact
,
&
Fact
::
rawValueChanged
,
this
,
&
MissionItem
::
_param3Changed
);
}
MissionItem
::
MissionItem
(
const
MissionItem
&
other
,
QObject
*
parent
)
...
...
@@ -123,6 +125,7 @@ MissionItem::MissionItem(const MissionItem& other, QObject* parent)
*
this
=
other
;
connect
(
&
_param2Fact
,
&
Fact
::
rawValueChanged
,
this
,
&
MissionItem
::
_param2Changed
);
connect
(
&
_param3Fact
,
&
Fact
::
rawValueChanged
,
this
,
&
MissionItem
::
_param3Changed
);
}
const
MissionItem
&
MissionItem
::
operator
=
(
const
MissionItem
&
other
)
...
...
@@ -384,7 +387,7 @@ QGeoCoordinate MissionItem::coordinate(void) const
return
QGeoCoordinate
(
param5
(),
param6
(),
param7
());
}
double
MissionItem
::
f
lightSpeed
(
void
)
const
double
MissionItem
::
specifiedF
lightSpeed
(
void
)
const
{
double
flightSpeed
=
std
::
numeric_limits
<
double
>::
quiet_NaN
();
...
...
@@ -395,9 +398,33 @@ double MissionItem::flightSpeed(void) const
return
flightSpeed
;
}
double
MissionItem
::
specifiedGimbalYaw
(
void
)
const
{
double
gimbalYaw
=
std
::
numeric_limits
<
double
>::
quiet_NaN
();
if
(
_commandFact
.
rawValue
().
toInt
()
==
MAV_CMD_DO_MOUNT_CONTROL
&&
_param7Fact
.
rawValue
().
toInt
()
==
MAV_MOUNT_MODE_MAVLINK_TARGETING
)
{
gimbalYaw
=
_param3Fact
.
rawValue
().
toDouble
();
}
return
gimbalYaw
;
}
void
MissionItem
::
_param2Changed
(
QVariant
value
)
{
if
(
_commandFact
.
rawValue
().
toInt
()
==
MAV_CMD_DO_CHANGE_SPEED
&&
_param2Fact
.
rawValue
().
toDouble
()
>
0
)
{
emit
flightSpeedChanged
(
value
.
toDouble
());
Q_UNUSED
(
value
);
double
flightSpeed
=
specifiedFlightSpeed
();
if
(
!
qIsNaN
(
flightSpeed
))
{
emit
specifiedFlightSpeedChanged
(
flightSpeed
);
}
}
void
MissionItem
::
_param3Changed
(
QVariant
value
)
{
Q_UNUSED
(
value
);
double
gimbalYaw
=
specifiedGimbalYaw
();
if
(
!
qIsNaN
(
gimbalYaw
))
{
emit
specifiedGimbalYawChanged
(
gimbalYaw
);
}
}
src/MissionManager/MissionItem.h
View file @
1e0e8d4d
...
...
@@ -77,7 +77,10 @@ public:
int
doJumpId
(
void
)
const
{
return
_doJumpId
;
}
/// @return Flight speed change value if this item supports it. If not it returns NaN.
double
flightSpeed
(
void
)
const
;
double
specifiedFlightSpeed
(
void
)
const
;
/// @return Flight gimbal yaw change value if this item supports it. If not it returns NaN.
double
specifiedGimbalYaw
(
void
)
const
;
void
setCommand
(
MAV_CMD
command
);
void
setSequenceNumber
(
int
sequenceNumber
);
...
...
@@ -100,13 +103,15 @@ public:
bool
relativeAltitude
(
void
)
const
{
return
frame
()
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
;
}
signals:
void
isCurrentItemChanged
(
bool
isCurrentItem
);
void
sequenceNumberChanged
(
int
sequenceNumber
);
void
flightSpeedChanged
(
double
flightSpeed
);
void
isCurrentItemChanged
(
bool
isCurrentItem
);
void
sequenceNumberChanged
(
int
sequenceNumber
);
void
specifiedFlightSpeedChanged
(
double
flightSpeed
);
void
specifiedGimbalYawChanged
(
double
gimbalYaw
);
private
slots
:
void
_param2Changed
(
QVariant
value
);
void
_param3Changed
(
QVariant
value
);
private:
bool
_convertJsonV1ToV2
(
const
QJsonObject
&
json
,
QJsonObject
&
v2Json
,
QString
&
errorString
);
...
...
src/MissionManager/MissionSettingsComplexItem.cc
View file @
1e0e8d4d
...
...
@@ -76,6 +76,10 @@ MissionSettingsComplexItem::MissionSettingsComplexItem(Vehicle* vehicle, QObject
connect
(
&
_missionEndActionFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionSettingsComplexItem
::
_setDirty
);
connect
(
&
_cameraSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
MissionSettingsComplexItem
::
_cameraSectionDirtyChanged
);
connect
(
&
_missionFlightSpeedFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionSettingsComplexItem
::
specifiedFlightSpeedChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
MissionSettingsComplexItem
::
specifiedGimbalYawChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
MissionSettingsComplexItem
::
specifiedGimbalYawChanged
);
}
...
...
@@ -266,12 +270,6 @@ double MissionSettingsComplexItem::complexDistance(void) const
return
0
;
}
void
MissionSettingsComplexItem
::
setCruiseSpeed
(
double
cruiseSpeed
)
{
// We don't care about cruise speed
Q_UNUSED
(
cruiseSpeed
);
}
void
MissionSettingsComplexItem
::
_setDirty
(
void
)
{
setDirty
(
true
);
...
...
@@ -310,3 +308,13 @@ void MissionSettingsComplexItem::_cameraSectionDirtyChanged(bool dirty)
setDirty
(
true
);
}
}
double
MissionSettingsComplexItem
::
specifiedFlightSpeed
(
void
)
{
return
_specifyMissionFlightSpeed
?
_missionFlightSpeedFact
.
rawValue
().
toDouble
()
:
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
MissionSettingsComplexItem
::
specifiedGimbalYaw
(
void
)
{
return
_cameraSection
.
specifyGimbal
()
?
_cameraSection
.
gimbalYaw
()
->
rawValue
().
toDouble
()
:
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
src/MissionManager/MissionSettingsComplexItem.h
View file @
1e0e8d4d
...
...
@@ -60,7 +60,6 @@ public:
int
lastSequenceNumber
(
void
)
const
final
;
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
final
;
double
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
final
;
void
setCruiseSpeed
(
double
cruiseSpeed
)
final
;
QString
mapVisualQML
(
void
)
const
final
{
return
QStringLiteral
(
"MissionSettingsMapVisual.qml"
);
}
// Overrides from VisualMissionItem
...
...
@@ -76,7 +75,8 @@ public:
QGeoCoordinate
coordinate
(
void
)
const
final
;
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
coordinate
();
}
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
flightSpeed
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedFlightSpeed
(
void
)
final
;
double
specifiedGimbalYaw
(
void
)
final
;
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
bool
coordinateHasRelativeAltitude
(
void
)
const
final
{
return
true
;
}
...
...
@@ -94,10 +94,10 @@ signals:
bool
specifyMissionFlightSpeedChanged
(
bool
specifyMissionFlightSpeed
);
private
slots
:
void
_setDirtyAndUpdateLastSequenceNumber
(
void
);
void
_setDirtyAndUpdateCoordinate
(
void
);
void
_setDirty
(
void
);
void
_cameraSectionDirtyChanged
(
bool
dirty
);
void
_setDirtyAndUpdateLastSequenceNumber
(
void
);
void
_setDirtyAndUpdateCoordinate
(
void
);
void
_setDirty
(
void
);
void
_cameraSectionDirtyChanged
(
bool
dirty
);
private:
bool
_specifyMissionFlightSpeed
;
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
1e0e8d4d
...
...
@@ -75,7 +75,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
setDefaultsForCommand
();
connect
(
&
_missionItem
,
&
MissionItem
::
flightSpeedChanged
,
this
,
&
SimpleMissionItem
::
f
lightSpeedChanged
);
connect
(
&
_missionItem
,
&
MissionItem
::
specifiedFlightSpeedChanged
,
this
,
&
SimpleMissionItem
::
specifiedF
lightSpeedChanged
);
connect
(
this
,
&
SimpleMissionItem
::
sequenceNumberChanged
,
this
,
&
SimpleMissionItem
::
lastSequenceNumberChanged
);
connect
(
this
,
&
SimpleMissionItem
::
cameraSectionChanged
,
this
,
&
SimpleMissionItem
::
_setDirtyFromSignal
);
...
...
@@ -637,9 +637,14 @@ void SimpleMissionItem::setSequenceNumber(int sequenceNumber)
}
}
double
SimpleMissionItem
::
f
lightSpeed
(
void
)
double
SimpleMissionItem
::
specifiedF
lightSpeed
(
void
)
{
return
missionItem
().
flightSpeed
();
return
missionItem
().
specifiedFlightSpeed
();
}
double
SimpleMissionItem
::
specifiedGimbalYaw
(
void
)
{
return
_cameraSection
->
available
()
?
_cameraSection
->
specifiedGimbalYaw
()
:
missionItem
().
specifiedGimbalYaw
();
}
void
SimpleMissionItem
::
scanForSections
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
,
Vehicle
*
vehicle
)
...
...
@@ -671,7 +676,10 @@ void SimpleMissionItem::_updateCameraSection(void)
connect
(
_cameraSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
SimpleMissionItem
::
_cameraSectionDirtyChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
availableChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_cameraSection
,
&
CameraSection
::
missionItemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_cameraSection
,
&
CameraSection
::
missionItemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_cameraSection
,
&
CameraSection
::
availableChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
emit
cameraSectionChanged
(
_cameraSection
);
}
...
...
src/MissionManager/SimpleMissionItem.h
View file @
1e0e8d4d
...
...
@@ -94,7 +94,8 @@ public:
QGeoCoordinate
coordinate
(
void
)
const
final
{
return
_missionItem
.
coordinate
();
}
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
coordinate
();
}
int
sequenceNumber
(
void
)
const
final
{
return
_missionItem
.
sequenceNumber
();
}
double
flightSpeed
(
void
)
final
;
double
specifiedFlightSpeed
(
void
)
final
;
double
specifiedGimbalYaw
(
void
)
final
;
QString
mapVisualQML
(
void
)
const
final
{
return
QStringLiteral
(
"SimpleItemMapVisual.qml"
);
}
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
...
...
src/MissionManager/SurveyMissionItem.cc
View file @
1e0e8d4d
...
...
@@ -122,12 +122,6 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
connect
(
&
_cameraTriggerFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_cameraTriggerChanged
);
connect
(
&
_cameraTriggerDistanceFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
timeBetweenShotsChanged
);
// NULL check since object creation during unit testing passes NULL for vehicle
if
(
_vehicle
)
{
connect
(
_vehicle
,
&
Vehicle
::
cruiseSpeedChanged
,
this
,
&
SurveyMissionItem
::
timeBetweenShotsChanged
);
connect
(
_vehicle
,
&
Vehicle
::
hoverSpeedChanged
,
this
,
&
SurveyMissionItem
::
timeBetweenShotsChanged
);
}
}
void
SurveyMissionItem
::
_setSurveyDistance
(
double
surveyDistance
)
...
...
@@ -881,10 +875,11 @@ double SurveyMissionItem::timeBetweenShots(void) const
return
_cruiseSpeed
==
0
?
0
:
_cameraTriggerDistanceFact
.
rawValue
().
toDouble
()
/
_cruiseSpeed
;
}
void
SurveyMissionItem
::
set
CruiseSpeed
(
double
cruiseSpeed
)
void
SurveyMissionItem
::
set
MissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
{
if
(
!
qFuzzyCompare
(
_cruiseSpeed
,
cruiseSpeed
))
{
_cruiseSpeed
=
cruiseSpeed
;
ComplexMissionItem
::
setMissionFlightStatus
(
missionFlightStatus
);
if
(
!
qFuzzyCompare
(
_cruiseSpeed
,
missionFlightStatus
.
vehicleSpeed
))
{
_cruiseSpeed
=
missionFlightStatus
.
vehicleSpeed
;
emit
timeBetweenShotsChanged
();
}
}
src/MissionManager/SurveyMissionItem.h
View file @
1e0e8d4d
...
...
@@ -100,7 +100,6 @@ public:
int
lastSequenceNumber
(
void
)
const
final
;
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
final
;
double
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
final
;
void
setCruiseSpeed
(
double
cruiseSpeed
)
final
;
QString
mapVisualQML
(
void
)
const
final
{
return
QStringLiteral
(
"SurveyMapVisual.qml"
);
}
...
...
@@ -117,8 +116,10 @@ public:
QGeoCoordinate
coordinate
(
void
)
const
final
{
return
_coordinate
;
}
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
_exitCoordinate
;
}
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
flightSpeed
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedFlightSpeed
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalYaw
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
final
;
bool
coordinateHasRelativeAltitude
(
void
)
const
final
{
return
_gridAltitudeRelativeFact
.
rawValue
().
toBool
();
}
bool
exitCoordinateHasRelativeAltitude
(
void
)
const
final
{
return
_gridAltitudeRelativeFact
.
rawValue
().
toBool
();
}
...
...
src/MissionManager/VisualMissionItem.cc
View file @
1e0e8d4d
...
...
@@ -31,6 +31,8 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent)
,
_altPercent
(
0.0
)
,
_azimuth
(
0.0
)
,
_distance
(
0.0
)
,
_missionGimbalYaw
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_missionVehicleYaw
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
{
}
...
...
@@ -117,3 +119,20 @@ void VisualMissionItem::setShowHomePosition(bool showHomePosition)
emit
showHomePositionChanged
(
_showHomePosition
);
}
}
void
VisualMissionItem
::
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
{
_missionFlightStatus
=
missionFlightStatus
;
if
(
_missionFlightStatus
.
gimbalYaw
!=
_missionGimbalYaw
)
{
_missionGimbalYaw
=
_missionFlightStatus
.
gimbalYaw
;
emit
missionGimbalYawChanged
(
_missionGimbalYaw
);
}
}
void
VisualMissionItem
::
setMissionVehicleYaw
(
double
vehicleYaw
)
{
if
(
!
qFuzzyCompare
(
_missionVehicleYaw
,
vehicleYaw
))
{
_missionVehicleYaw
=
vehicleYaw
;
emit
missionVehicleYawChanged
(
_missionVehicleYaw
);
}
}
src/MissionManager/VisualMissionItem.h
View file @
1e0e8d4d
This diff is collapsed.
Click to expand it.
src/QmlControls/MissionItemIndexLabel.qml
View file @
1e0e8d4d
...
...
@@ -7,34 +7,71 @@ import QGroundControl.Palette 1.0
Canvas
{
id
:
root
width
:
_width
+
(
_singleChar
?
0
:
_label
.
width
)
height
:
specifiesCoordinate
?
(
_width
*
1.5
)
:
_
width
width
:
_width
height
:
width
signal
clicked
property
alias
label
:
_label
.
text
property
string
label
property
bool
checked
:
false
property
bool
small
:
false
property
var
color
:
checked
?
"
green
"
:
qgcPal
.
mapButtonHighlight
property
real
anchorPointX
:
_width
/
2
property
real
anchorPointY
:
_width
*
1.5
property
real
anchorPointY
:
_width
/
2
property
bool
specifiesCoordinate
:
true
property
real
gimbalYaw
property
real
vehicleYaw
property
bool
showGimbalYaw
:
false
property
real
_width
:
small
?
ScreenTools
.
defaultFontPixelHeight
*
ScreenTools
.
smallFontPointRatio
*
1.25
:
ScreenTools
.
defaultFontPixelHeight
*
1.25
property
bool
_singleChar
:
_label
.
text
.
length
<=
1
property
real
_width
:
showGimbalYaw
?
_gimbalYawRadius
*
2
:
_indicatorRadius
*
2
property
bool
_singleChar
:
_label
.
text
.
length
<=
1
property
real
_gimbalYawRadius
:
ScreenTools
.
defaultFontPixelHeight
property
real
_indicatorRadius
:
small
?
(
ScreenTools
.
defaultFontPixelHeight
*
ScreenTools
.
smallFontPointRatio
*
1.25
/
2
)
:
(
ScreenTools
.
defaultFontPixelHeight
*
0.66
)
property
real
_gimbalRadians
:
degreesToRadians
(
vehicleYaw
+
gimbalYaw
-
90
)
onColorChanged
:
requestPaint
()
onColorChanged
:
requestPaint
()
onShowGimbalYawChanged
:
requestPaint
()
onGimbalYawChanged
:
requestPaint
()
onVehicleYawChanged
:
requestPaint
()
QGCPalette
{
id
:
qgcPal
}
function
degreesToRadians
(
degrees
)
{
return
(
Math
.
PI
/
180
)
*
degrees
}
function
paintGimbalYaw
(
context
)
{
if
(
showGimbalYaw
)
{
context
.
save
()
context
.
globalAlpha
=
0.75
context
.
beginPath
()
context
.
moveTo
(
anchorPointX
,
anchorPointY
)
context
.
arc
(
anchorPointX
,
anchorPointY
,
_gimbalYawRadius
,
_gimbalRadians
+
degreesToRadians
(
45
),
_gimbalRadians
+
degreesToRadians
(
-
45
),
true
/* clockwise */
)
context
.
closePath
()
context
.
fillStyle
=
"
white
"
context
.
fill
()
context
.
restore
()
}
}
function
paintSingleCoordinate
(
context
)
{
context
.
beginPath
()
context
.
arc
(
_width
/
2
,
_width
/
2
,
_width
/
2
,
(
Math
.
PI
/
8
)
*
7
,
Math
.
PI
/
8
);
context
.
lineTo
(
_width
/
2
,
_width
*
1.5
)
context
.
closePath
()
context
.
fillStyle
=
color
context
.
fill
()
}
function
paintSingleNoCoordinate
(
context
)
{
context
.
arc
(
_width
/
2
,
_width
/
2
,
_width
/
2
,
Math
.
PI
*
2
,
0
);
context
.
save
()
context
.
beginPath
()
context
.
translate
(
anchorPointX
,
anchorPointY
)
context
.
arc
(
0
,
0
,
_indicatorRadius
,
Math
.
PI
*
2
,
0
);
context
.
closePath
()
context
.
fillStyle
=
color
context
.
fill
()
context
.
restore
()
}
function
paintMultipleCoordinate
(
context
)
{
...
...
@@ -47,8 +84,9 @@ Canvas {
onPaint
:
{
var
context
=
getContext
(
"
2d
"
)
context
.
reset
()
context
.
beginPath
()
context
.
clearRect
(
0
,
0
,
width
,
height
)
paintGimbalYaw
(
context
)
/*
if (_singleChar) {
if (specifiesCoordinate) {
paintSingleCoordinate(context)
...
...
@@ -58,19 +96,21 @@ Canvas {
} else {
paintMultipleCoordinate(context)
}
context
.
closePath
()
context
.
fillStyle
=
color
context
.
fill
()
*/
paintSingleNoCoordinate
(
context
)
}
QGCLabel
{
id
:
_label
x
:
Math
.
round
((
_width
/
2
)
-
(
_singleChar
?
(
width
/
2
)
:
(
ScreenTools
.
defaultFontPixelWidth
/
2
)))
y
:
Math
.
round
((
_width
/
2
)
-
(
height
/
2
))
color
:
"
white
"
font.pointSize
:
small
?
ScreenTools
.
smallFontPointSize
:
ScreenTools
.
defaultFontPointSize
onWidthChanged
:
requestPaint
()
id
:
_label
anchors.centerIn
:
parent
width
:
_indicatorRadius
*
2
height
:
width
horizontalAlignment
:
Text
.
AlignHCenter
verticalAlignment
:
Text
.
AlignVCenter
color
:
"
white
"
font.pointSize
:
ScreenTools
.
defaultFontPointSize
fontSizeMode
:
Text
.
HorizontalFit
text
:
label
}
QGCMouseArea
{
...
...
src/Vehicle/Vehicle.cc
View file @
1e0e8d4d
...
...
@@ -102,8 +102,8 @@ Vehicle::Vehicle(LinkInterface* link,
,
_onboardControlSensorsUnhealthy
(
0
)
,
_gpsRawIntMessageAvailable
(
false
)
,
_globalPositionIntMessageAvailable
(
false
)
,
_
c
ruiseSpeed
(
_settingsManager
->
appSettings
()
->
offlineEditingCruiseSpeed
()
->
rawValue
().
toDouble
())
,
_
h
overSpeed
(
_settingsManager
->
appSettings
()
->
offlineEditingHoverSpeed
()
->
rawValue
().
toDouble
())
,
_
defaultC
ruiseSpeed
(
_settingsManager
->
appSettings
()
->
offlineEditingCruiseSpeed
()
->
rawValue
().
toDouble
())
,
_
defaultH
overSpeed
(
_settingsManager
->
appSettings
()
->
offlineEditingHoverSpeed
()
->
rawValue
().
toDouble
())
,
_telemetryRRSSI
(
0
)
,
_telemetryLRSSI
(
0
)
,
_telemetryRXErrors
(
0
)
...
...
@@ -265,8 +265,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
,
_onboardControlSensorsUnhealthy
(
0
)
,
_gpsRawIntMessageAvailable
(
false
)
,
_globalPositionIntMessageAvailable
(
false
)
,
_
c
ruiseSpeed
(
_settingsManager
->
appSettings
()
->
offlineEditingCruiseSpeed
()
->
rawValue
().
toDouble
())
,
_
h
overSpeed
(
_settingsManager
->
appSettings
()
->
offlineEditingHoverSpeed
()
->
rawValue
().
toDouble
())
,
_
defaultC
ruiseSpeed
(
_settingsManager
->
appSettings
()
->
offlineEditingCruiseSpeed
()
->
rawValue
().
toDouble
())
,
_
defaultH
overSpeed
(
_settingsManager
->
appSettings
()
->
offlineEditingHoverSpeed
()
->
rawValue
().
toDouble
())
,
_vehicleCapabilitiesKnown
(
true
)
,
_supportsMissionItemInt
(
false
)
,
_connectionLost
(
false
)
...
...
@@ -385,14 +385,14 @@ void Vehicle::_offlineVehicleTypeSettingChanged(QVariant value)
void
Vehicle
::
_offlineCruiseSpeedSettingChanged
(
QVariant
value
)
{
_
c
ruiseSpeed
=
value
.
toDouble
();
emit
cruiseSpeedChanged
(
_c
ruiseSpeed
);
_
defaultC
ruiseSpeed
=
value
.
toDouble
();
emit
defaultCruiseSpeedChanged
(
_defaultC
ruiseSpeed
);
}
void
Vehicle
::
_offlineHoverSpeedSettingChanged
(
QVariant
value
)
{
_
h
overSpeed
=
value
.
toDouble
();
emit
hoverSpeedChanged
(
_h
overSpeed
);
_
defaultH
overSpeed
=
value
.
toDouble
();
emit
defaultHoverSpeedChanged
(
_defaultH
overSpeed
);
}
QString
Vehicle
::
firmwareTypeString
(
void
)
const
...
...
src/Vehicle/Vehicle.h
View file @
1e0e8d4d
...
...
@@ -574,8 +574,8 @@ public:
QString
missionFlightMode
()
const
;
QString
rtlFlightMode
()
const
;
QString
takeControlFlightMode
()
const
;
double
cruiseSpeed
()
const
{
return
_c
ruiseSpeed
;
}
double
hoverSpeed
()
const
{
return
_h
overSpeed
;
}
double
defaultCruiseSpeed
()
const
{
return
_defaultC
ruiseSpeed
;
}
double
defaultHoverSpeed
()
const
{
return
_defaultH
overSpeed
;
}
QString
firmwareTypeString
()
const
;
QString
vehicleTypeString
()
const
;
int
telemetryRRSSI
()
{
return
_telemetryRRSSI
;
}
...
...
@@ -690,8 +690,8 @@ signals:
void
prearmErrorChanged
(
const
QString
&
prearmError
);
void
soloFirmwareChanged
(
bool
soloFirmware
);
void
unhealthySensorsChanged
(
void
);
void
c
ruiseSpeedChanged
(
double
cruiseSpeed
);
void
h
overSpeedChanged
(
double
hoverSpeed
);
void
defaultC
ruiseSpeedChanged
(
double
cruiseSpeed
);
void
defaultH
overSpeedChanged
(
double
hoverSpeed
);
void
firmwareTypeChanged
(
void
);
void
vehicleTypeChanged
(
void
);
...
...
@@ -872,8 +872,8 @@ private:
uint32_t
_onboardControlSensorsUnhealthy
;
bool
_gpsRawIntMessageAvailable
;
bool
_globalPositionIntMessageAvailable
;
double
_
c
ruiseSpeed
;
double
_
h
overSpeed
;
double
_
defaultC
ruiseSpeed
;
double
_
defaultH
overSpeed
;
int
_telemetryRRSSI
;
int
_telemetryLRSSI
;
uint32_t
_telemetryRXErrors
;
...
...
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