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
1ac6cd32
Commit
1ac6cd32
authored
Mar 23, 2018
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
FW Landing Glide Slope support
parent
2296ed0d
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
138 additions
and
113 deletions
+138
-113
FWLandingPattern.FactMetaData.json
src/MissionManager/FWLandingPattern.FactMetaData.json
+4
-4
FixedWingLandingComplexItem.cc
src/MissionManager/FixedWingLandingComplexItem.cc
+73
-25
FixedWingLandingComplexItem.h
src/MissionManager/FixedWingLandingComplexItem.h
+38
-32
FWLandingPatternEditor.qml
src/PlanView/FWLandingPatternEditor.qml
+23
-52
No files found.
src/MissionManager/FWLandingPattern.FactMetaData.json
View file @
1ac6cd32
...
@@ -44,12 +44,12 @@
...
@@ -44,12 +44,12 @@
"defaultValue"
:
0.0
"defaultValue"
:
0.0
},
},
{
{
"name"
:
"
DescentRat
e"
,
"name"
:
"
GlideSlop
e"
,
"shortDescription"
:
"
Descent rate between landing and loiter altitude
."
,
"shortDescription"
:
"
The glide slope between the loiter and landing point
."
,
"type"
:
"double"
,
"type"
:
"double"
,
"units"
:
"
%
"
,
"units"
:
"
deg
"
,
"min"
:
0.1
,
"min"
:
0.1
,
"max"
:
10
0
,
"max"
:
9
0
,
"decimalPlaces"
:
1
,
"decimalPlaces"
:
1
,
"defaultValue"
:
12.0
"defaultValue"
:
12.0
}
}
...
...
src/MissionManager/FixedWingLandingComplexItem.cc
View file @
1ac6cd32
...
@@ -25,15 +25,19 @@ const char* FixedWingLandingComplexItem::landingHeadingName = "LandingHead
...
@@ -25,15 +25,19 @@ const char* FixedWingLandingComplexItem::landingHeadingName = "LandingHead
const
char
*
FixedWingLandingComplexItem
::
loiterAltitudeName
=
"LoiterAltitude"
;
const
char
*
FixedWingLandingComplexItem
::
loiterAltitudeName
=
"LoiterAltitude"
;
const
char
*
FixedWingLandingComplexItem
::
loiterRadiusName
=
"LoiterRadius"
;
const
char
*
FixedWingLandingComplexItem
::
loiterRadiusName
=
"LoiterRadius"
;
const
char
*
FixedWingLandingComplexItem
::
landingAltitudeName
=
"LandingAltitude"
;
const
char
*
FixedWingLandingComplexItem
::
landingAltitudeName
=
"LandingAltitude"
;
const
char
*
FixedWingLandingComplexItem
::
fallRateName
=
"DescentRat
e"
;
const
char
*
FixedWingLandingComplexItem
::
glideSlopeName
=
"GlideSlop
e"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonLoiterCoordinateKey
=
"loiterCoordinate"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonLoiterCoordinateKey
=
"loiterCoordinate"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonLoiterRadiusKey
=
"loiterRadius"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonLoiterRadiusKey
=
"loiterRadius"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonLoiterClockwiseKey
=
"loiterClockwise"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonLoiterClockwiseKey
=
"loiterClockwise"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonLoiterAltitudeRelativeKey
=
"loiterAltitudeRelative"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonLandingCoordinateKey
=
"landCoordinate"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonLandingCoordinateKey
=
"landCoordinate"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonLandingAltitudeRelativeKey
=
"landAltitudeRelative"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonValueSetIsDistanceKey
=
"valueSetIsDistance"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonAltitudesAreRelativeKey
=
"altitudesAreRelative"
;
// Usage deprecated
const
char
*
FixedWingLandingComplexItem
::
_jsonFallRateKey
=
"fallRate"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonFallRateKey
=
"fallRate"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonLandingAltitudeRelativeKey
=
"landAltitudeRelative"
;
const
char
*
FixedWingLandingComplexItem
::
_jsonLoiterAltitudeRelativeKey
=
"loiterAltitudeRelative"
;
FixedWingLandingComplexItem
::
FixedWingLandingComplexItem
(
Vehicle
*
vehicle
,
QObject
*
parent
)
FixedWingLandingComplexItem
::
FixedWingLandingComplexItem
(
Vehicle
*
vehicle
,
QObject
*
parent
)
:
ComplexMissionItem
(
vehicle
,
parent
)
:
ComplexMissionItem
(
vehicle
,
parent
)
...
@@ -47,10 +51,10 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObje
...
@@ -47,10 +51,10 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObje
,
_loiterRadiusFact
(
_metaDataMap
[
loiterRadiusName
])
,
_loiterRadiusFact
(
_metaDataMap
[
loiterRadiusName
])
,
_landingHeadingFact
(
_metaDataMap
[
landingHeadingName
])
,
_landingHeadingFact
(
_metaDataMap
[
landingHeadingName
])
,
_landingAltitudeFact
(
_metaDataMap
[
landingAltitudeName
])
,
_landingAltitudeFact
(
_metaDataMap
[
landingAltitudeName
])
,
_
fallRateFact
(
_metaDataMap
[
fallRat
eName
])
,
_
glideSlopeFact
(
_metaDataMap
[
glideSlop
eName
])
,
_loiterClockwise
(
true
)
,
_loiterClockwise
(
true
)
,
_
loiterAltitudeRelative
(
true
)
,
_
altitudesAreRelative
(
true
)
,
_
landingAltitudeRelative
(
true
)
,
_
valueSetIsDistance
(
true
)
{
{
_editorQml
=
"qrc:/qml/FWLandingPatternEditor.qml"
;
_editorQml
=
"qrc:/qml/FWLandingPatternEditor.qml"
;
...
@@ -66,6 +70,8 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObje
...
@@ -66,6 +70,8 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObje
connect
(
this
,
&
FixedWingLandingComplexItem
::
loiterCoordinateChanged
,
this
,
&
FixedWingLandingComplexItem
::
_recalcFromCoordinateChange
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
loiterCoordinateChanged
,
this
,
&
FixedWingLandingComplexItem
::
_recalcFromCoordinateChange
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
landingCoordinateChanged
,
this
,
&
FixedWingLandingComplexItem
::
_recalcFromCoordinateChange
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
landingCoordinateChanged
,
this
,
&
FixedWingLandingComplexItem
::
_recalcFromCoordinateChange
);
connect
(
&
_glideSlopeFact
,
&
Fact
::
valueChanged
,
this
,
&
FixedWingLandingComplexItem
::
_glideSlopeChanged
);
connect
(
&
_loiterAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
&
_loiterAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
&
_landingAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
&
_landingAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
&
_landingDistanceFact
,
&
Fact
::
valueChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
&
_landingDistanceFact
,
&
Fact
::
valueChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
...
@@ -74,11 +80,10 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObje
...
@@ -74,11 +80,10 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObje
connect
(
this
,
&
FixedWingLandingComplexItem
::
loiterCoordinateChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
loiterCoordinateChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
landingCoordinateChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
landingCoordinateChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
loiterClockwiseChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
loiterClockwiseChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
loiterAltitudeRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
altitudesAreRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
landingAltitudeRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
loiterAltitudeRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
coordinateHasRelativeAltitudeChanged
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
altitudesAreRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
coordinateHasRelativeAltitudeChanged
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
landingAltitudeRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
exitCoordinateHasRelativeAltitudeChanged
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
altitudesAreRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
exitCoordinateHasRelativeAltitudeChanged
);
}
}
int
FixedWingLandingComplexItem
::
lastSequenceNumber
(
void
)
const
int
FixedWingLandingComplexItem
::
lastSequenceNumber
(
void
)
const
...
@@ -99,7 +104,7 @@ void FixedWingLandingComplexItem::save(QJsonArray& missionItems)
...
@@ -99,7 +104,7 @@ void FixedWingLandingComplexItem::save(QJsonArray& missionItems)
{
{
QJsonObject
saveObject
;
QJsonObject
saveObject
;
saveObject
[
JsonHelper
::
jsonVersionKey
]
=
1
;
saveObject
[
JsonHelper
::
jsonVersionKey
]
=
2
;
saveObject
[
VisualMissionItem
::
jsonTypeKey
]
=
VisualMissionItem
::
jsonTypeComplexItemValue
;
saveObject
[
VisualMissionItem
::
jsonTypeKey
]
=
VisualMissionItem
::
jsonTypeComplexItemValue
;
saveObject
[
ComplexMissionItem
::
jsonComplexItemTypeKey
]
=
jsonComplexItemTypeValue
;
saveObject
[
ComplexMissionItem
::
jsonComplexItemTypeKey
]
=
jsonComplexItemTypeValue
;
...
@@ -116,10 +121,10 @@ void FixedWingLandingComplexItem::save(QJsonArray& missionItems)
...
@@ -116,10 +121,10 @@ void FixedWingLandingComplexItem::save(QJsonArray& missionItems)
JsonHelper
::
saveGeoCoordinate
(
coordinate
,
true
/* writeAltitude */
,
jsonCoordinate
);
JsonHelper
::
saveGeoCoordinate
(
coordinate
,
true
/* writeAltitude */
,
jsonCoordinate
);
saveObject
[
_jsonLandingCoordinateKey
]
=
jsonCoordinate
;
saveObject
[
_jsonLandingCoordinateKey
]
=
jsonCoordinate
;
saveObject
[
_jsonLoiterRadiusKey
]
=
_loiterRadiusFact
.
rawValue
().
toDouble
();
saveObject
[
_jsonLoiterRadiusKey
]
=
_loiterRadiusFact
.
rawValue
().
toDouble
();
saveObject
[
_jsonLoiterClockwiseKey
]
=
_loiterClockwise
;
saveObject
[
_jsonLoiterClockwiseKey
]
=
_loiterClockwise
;
saveObject
[
_json
LoiterAltitudeRelativeKey
]
=
_loiterAltitud
eRelative
;
saveObject
[
_json
AltitudesAreRelativeKey
]
=
_altitudesAr
eRelative
;
saveObject
[
_json
LandingAltitudeRelativeKey
]
=
_landingAltitudeRelativ
e
;
saveObject
[
_json
ValueSetIsDistanceKey
]
=
_valueSetIsDistanc
e
;
missionItems
.
append
(
saveObject
);
missionItems
.
append
(
saveObject
);
}
}
...
@@ -142,9 +147,7 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq
...
@@ -142,9 +147,7 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq
{
_jsonLoiterCoordinateKey
,
QJsonValue
::
Array
,
true
},
{
_jsonLoiterCoordinateKey
,
QJsonValue
::
Array
,
true
},
{
_jsonLoiterRadiusKey
,
QJsonValue
::
Double
,
true
},
{
_jsonLoiterRadiusKey
,
QJsonValue
::
Double
,
true
},
{
_jsonLoiterClockwiseKey
,
QJsonValue
::
Bool
,
true
},
{
_jsonLoiterClockwiseKey
,
QJsonValue
::
Bool
,
true
},
{
_jsonLoiterAltitudeRelativeKey
,
QJsonValue
::
Bool
,
true
},
{
_jsonLandingCoordinateKey
,
QJsonValue
::
Array
,
true
},
{
_jsonLandingCoordinateKey
,
QJsonValue
::
Array
,
true
},
{
_jsonLandingAltitudeRelativeKey
,
QJsonValue
::
Bool
,
true
},
};
};
if
(
!
JsonHelper
::
validateKeys
(
complexObject
,
keyInfoList
,
errorString
))
{
if
(
!
JsonHelper
::
validateKeys
(
complexObject
,
keyInfoList
,
errorString
))
{
return
false
;
return
false
;
...
@@ -161,6 +164,31 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq
...
@@ -161,6 +164,31 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq
_ignoreRecalcSignals
=
true
;
_ignoreRecalcSignals
=
true
;
int
version
=
complexObject
[
JsonHelper
::
jsonVersionKey
].
toInt
();
if
(
version
==
1
)
{
bool
loiterAltitudeRelative
=
complexObject
[
_jsonLoiterAltitudeRelativeKey
].
toBool
();
bool
landingAltitudeRelative
=
complexObject
[
_jsonLandingAltitudeRelativeKey
].
toBool
();
if
(
loiterAltitudeRelative
!=
landingAltitudeRelative
)
{
qgcApp
()
->
showMessage
(
tr
(
"Fixed Wing Landing Pattern: "
"Setting the loiter and landing altitudes with different settings for altitude relative is no longer supported. "
"Both have been set to altitude relative. Be sure to adjust/check your plan prior to flight."
));
_altitudesAreRelative
=
true
;
}
else
{
_altitudesAreRelative
=
loiterAltitudeRelative
;
}
}
else
if
(
version
==
2
)
{
QList
<
JsonHelper
::
KeyValidateInfo
>
v2KeyInfoList
=
{
{
_jsonAltitudesAreRelativeKey
,
QJsonValue
::
Bool
,
true
},
};
if
(
!
JsonHelper
::
validateKeys
(
complexObject
,
v2KeyInfoList
,
errorString
))
{
return
false
;
}
}
else
{
errorString
=
tr
(
"%1 complex item version %2 not supported"
).
arg
(
jsonComplexItemTypeValue
).
arg
(
version
);
_ignoreRecalcSignals
=
false
;
return
false
;
}
QGeoCoordinate
coordinate
;
QGeoCoordinate
coordinate
;
if
(
!
JsonHelper
::
loadGeoCoordinate
(
complexObject
[
_jsonLoiterCoordinateKey
],
true
/* altitudeRequired */
,
coordinate
,
errorString
))
{
if
(
!
JsonHelper
::
loadGeoCoordinate
(
complexObject
[
_jsonLoiterCoordinateKey
],
true
/* altitudeRequired */
,
coordinate
,
errorString
))
{
return
false
;
return
false
;
...
@@ -175,9 +203,8 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq
...
@@ -175,9 +203,8 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq
_landingAltitudeFact
.
setRawValue
(
coordinate
.
altitude
());
_landingAltitudeFact
.
setRawValue
(
coordinate
.
altitude
());
_loiterRadiusFact
.
setRawValue
(
complexObject
[
_jsonLoiterRadiusKey
].
toDouble
());
_loiterRadiusFact
.
setRawValue
(
complexObject
[
_jsonLoiterRadiusKey
].
toDouble
());
_loiterClockwise
=
complexObject
[
_jsonLoiterClockwiseKey
].
toBool
();
_loiterClockwise
=
complexObject
[
_jsonLoiterClockwiseKey
].
toBool
();
_loiterAltitudeRelative
=
complexObject
[
_jsonLoiterAltitudeRelativeKey
].
toBool
();
_altitudesAreRelative
=
complexObject
[
_jsonAltitudesAreRelativeKey
].
toBool
();
_landingAltitudeRelative
=
complexObject
[
_jsonLandingAltitudeRelativeKey
].
toBool
();
_landingCoordSet
=
true
;
_landingCoordSet
=
true
;
...
@@ -215,7 +242,7 @@ void FixedWingLandingComplexItem::appendMissionItems(QList<MissionItem*>& items,
...
@@ -215,7 +242,7 @@ void FixedWingLandingComplexItem::appendMissionItems(QList<MissionItem*>& items,
float
loiterRadius
=
_loiterRadiusFact
.
rawValue
().
toDouble
()
*
(
_loiterClockwise
?
1.0
:
-
1.0
);
float
loiterRadius
=
_loiterRadiusFact
.
rawValue
().
toDouble
()
*
(
_loiterClockwise
?
1.0
:
-
1.0
);
item
=
new
MissionItem
(
seqNum
++
,
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_NAV_LOITER_TO_ALT
,
MAV_CMD_NAV_LOITER_TO_ALT
,
_
loiterAltitud
eRelative
?
MAV_FRAME_GLOBAL_RELATIVE_ALT
:
MAV_FRAME_GLOBAL
,
_
altitudesAr
eRelative
?
MAV_FRAME_GLOBAL_RELATIVE_ALT
:
MAV_FRAME_GLOBAL
,
1.0
,
// Heading required = true
1.0
,
// Heading required = true
loiterRadius
,
// Loiter radius
loiterRadius
,
// Loiter radius
0.0
,
// param 3 - unused
0.0
,
// param 3 - unused
...
@@ -230,7 +257,7 @@ void FixedWingLandingComplexItem::appendMissionItems(QList<MissionItem*>& items,
...
@@ -230,7 +257,7 @@ void FixedWingLandingComplexItem::appendMissionItems(QList<MissionItem*>& items,
item
=
new
MissionItem
(
seqNum
++
,
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_NAV_LAND
,
MAV_CMD_NAV_LAND
,
_
landingAltitud
eRelative
?
MAV_FRAME_GLOBAL_RELATIVE_ALT
:
MAV_FRAME_GLOBAL
,
_
altitudesAr
eRelative
?
MAV_FRAME_GLOBAL_RELATIVE_ALT
:
MAV_FRAME_GLOBAL
,
0.0
,
0.0
,
0.0
,
0.0
,
// param 1-4
0.0
,
0.0
,
0.0
,
0.0
,
// param 1-4
_landingCoordinate
.
latitude
(),
_landingCoordinate
.
latitude
(),
_landingCoordinate
.
longitude
(),
_landingCoordinate
.
longitude
(),
...
@@ -261,6 +288,7 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, V
...
@@ -261,6 +288,7 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, V
missionItemLand
.
param1
()
!=
0
||
missionItemLand
.
param2
()
!=
0
||
missionItemLand
.
param3
()
!=
0
||
missionItemLand
.
param4
()
==
1.0
)
{
missionItemLand
.
param1
()
!=
0
||
missionItemLand
.
param2
()
!=
0
||
missionItemLand
.
param3
()
!=
0
||
missionItemLand
.
param4
()
==
1.0
)
{
return
false
;
return
false
;
}
}
MAV_FRAME
landPointFrame
=
missionItemLand
.
frame
();
item
=
visualItems
->
value
<
SimpleMissionItem
*>
(
lastItem
--
);
item
=
visualItems
->
value
<
SimpleMissionItem
*>
(
lastItem
--
);
if
(
!
item
)
{
if
(
!
item
)
{
...
@@ -268,7 +296,7 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, V
...
@@ -268,7 +296,7 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, V
}
}
MissionItem
&
missionItemLoiter
=
item
->
missionItem
();
MissionItem
&
missionItemLoiter
=
item
->
missionItem
();
if
(
missionItemLoiter
.
command
()
!=
MAV_CMD_NAV_LOITER_TO_ALT
||
if
(
missionItemLoiter
.
command
()
!=
MAV_CMD_NAV_LOITER_TO_ALT
||
!
(
missionItemLoiter
.
frame
()
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
||
missionItemLoiter
.
frame
()
==
MAV_FRAME_GLOBAL
)
||
missionItemLoiter
.
frame
()
!=
landPointFrame
||
missionItemLoiter
.
param1
()
!=
1.0
||
missionItemLoiter
.
param3
()
!=
0
||
missionItemLoiter
.
param4
()
!=
1.0
)
{
missionItemLoiter
.
param1
()
!=
1.0
||
missionItemLoiter
.
param3
()
!=
0
||
missionItemLoiter
.
param4
()
!=
1.0
)
{
return
false
;
return
false
;
}
}
...
@@ -289,14 +317,13 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, V
...
@@ -289,14 +317,13 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, V
complexItem
->
_ignoreRecalcSignals
=
true
;
complexItem
->
_ignoreRecalcSignals
=
true
;
complexItem
->
_
loiterAltitudeRelative
=
missionItemLoiter
.
frame
()
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
;
complexItem
->
_
altitudesAreRelative
=
landPointFrame
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
;
complexItem
->
_loiterRadiusFact
.
setRawValue
(
qAbs
(
missionItemLoiter
.
param2
()));
complexItem
->
_loiterRadiusFact
.
setRawValue
(
qAbs
(
missionItemLoiter
.
param2
()));
complexItem
->
_loiterClockwise
=
missionItemLoiter
.
param2
()
>
0
;
complexItem
->
_loiterClockwise
=
missionItemLoiter
.
param2
()
>
0
;
complexItem
->
_loiterCoordinate
.
setLatitude
(
missionItemLoiter
.
param5
());
complexItem
->
_loiterCoordinate
.
setLatitude
(
missionItemLoiter
.
param5
());
complexItem
->
_loiterCoordinate
.
setLongitude
(
missionItemLoiter
.
param6
());
complexItem
->
_loiterCoordinate
.
setLongitude
(
missionItemLoiter
.
param6
());
complexItem
->
_loiterAltitudeFact
.
setRawValue
(
missionItemLoiter
.
param7
());
complexItem
->
_loiterAltitudeFact
.
setRawValue
(
missionItemLoiter
.
param7
());
complexItem
->
_landingAltitudeRelative
=
missionItemLand
.
frame
()
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
;
complexItem
->
_landingCoordinate
.
setLatitude
(
missionItemLand
.
param5
());
complexItem
->
_landingCoordinate
.
setLatitude
(
missionItemLand
.
param5
());
complexItem
->
_landingCoordinate
.
setLongitude
(
missionItemLand
.
param6
());
complexItem
->
_landingCoordinate
.
setLongitude
(
missionItemLand
.
param6
());
complexItem
->
_landingAltitudeFact
.
setRawValue
(
missionItemLand
.
param7
());
complexItem
->
_landingAltitudeFact
.
setRawValue
(
missionItemLand
.
param7
());
...
@@ -418,6 +445,7 @@ void FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange(void)
...
@@ -418,6 +445,7 @@ void FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange(void)
// Adjusted:
// Adjusted:
// loiter
// loiter
// loiter tangent
// loiter tangent
// glide slope
if
(
!
_ignoreRecalcSignals
&&
_landingCoordSet
)
{
if
(
!
_ignoreRecalcSignals
&&
_landingCoordSet
)
{
// These are our known values
// These are our known values
...
@@ -442,6 +470,7 @@ void FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange(void)
...
@@ -442,6 +470,7 @@ void FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange(void)
emit
loiterTangentCoordinateChanged
(
_loiterTangentCoordinate
);
emit
loiterTangentCoordinateChanged
(
_loiterTangentCoordinate
);
emit
loiterCoordinateChanged
(
_loiterCoordinate
);
emit
loiterCoordinateChanged
(
_loiterCoordinate
);
emit
coordinateChanged
(
_loiterCoordinate
);
emit
coordinateChanged
(
_loiterCoordinate
);
_calcGlideSlope
();
_ignoreRecalcSignals
=
false
;
_ignoreRecalcSignals
=
false
;
}
}
}
}
...
@@ -467,6 +496,7 @@ void FixedWingLandingComplexItem::_recalcFromCoordinateChange(void)
...
@@ -467,6 +496,7 @@ void FixedWingLandingComplexItem::_recalcFromCoordinateChange(void)
// loiter tangent
// loiter tangent
// heading
// heading
// distance
// distance
// glide slope
if
(
!
_ignoreRecalcSignals
&&
_landingCoordSet
)
{
if
(
!
_ignoreRecalcSignals
&&
_landingCoordSet
)
{
// These are our known values
// These are our known values
...
@@ -493,6 +523,7 @@ void FixedWingLandingComplexItem::_recalcFromCoordinateChange(void)
...
@@ -493,6 +523,7 @@ void FixedWingLandingComplexItem::_recalcFromCoordinateChange(void)
_landingHeadingFact
.
setRawValue
(
heading
);
_landingHeadingFact
.
setRawValue
(
heading
);
_landingDistanceFact
.
setRawValue
(
landToTangentDistance
);
_landingDistanceFact
.
setRawValue
(
landToTangentDistance
);
emit
loiterTangentCoordinateChanged
(
_loiterTangentCoordinate
);
emit
loiterTangentCoordinateChanged
(
_loiterTangentCoordinate
);
_calcGlideSlope
();
_ignoreRecalcSignals
=
false
;
_ignoreRecalcSignals
=
false
;
}
}
}
}
...
@@ -519,3 +550,20 @@ void FixedWingLandingComplexItem::applyNewAltitude(double newAltitude)
...
@@ -519,3 +550,20 @@ void FixedWingLandingComplexItem::applyNewAltitude(double newAltitude)
{
{
_loiterAltitudeFact
.
setRawValue
(
newAltitude
);
_loiterAltitudeFact
.
setRawValue
(
newAltitude
);
}
}
void
FixedWingLandingComplexItem
::
_glideSlopeChanged
(
void
)
{
if
(
!
_ignoreRecalcSignals
)
{
double
landingAltDifference
=
_loiterAltitudeFact
.
rawValue
().
toDouble
()
-
_landingAltitudeFact
.
rawValue
().
toDouble
();
double
glideSlope
=
_glideSlopeFact
.
rawValue
().
toDouble
();
_landingDistanceFact
.
setRawValue
(
landingAltDifference
/
qTan
(
qDegreesToRadians
(
glideSlope
)));
}
}
void
FixedWingLandingComplexItem
::
_calcGlideSlope
(
void
)
{
double
landingAltDifference
=
_loiterAltitudeFact
.
rawValue
().
toDouble
()
-
_landingAltitudeFact
.
rawValue
().
toDouble
();
double
landingDistance
=
_landingDistanceFact
.
rawValue
().
toDouble
();
_glideSlopeFact
.
setRawValue
(
qRadiansToDegrees
(
qAtan
(
landingAltDifference
/
landingDistance
)));
}
src/MissionManager/FixedWingLandingComplexItem.h
View file @
1ac6cd32
...
@@ -24,26 +24,26 @@ class FixedWingLandingComplexItem : public ComplexMissionItem
...
@@ -24,26 +24,26 @@ class FixedWingLandingComplexItem : public ComplexMissionItem
public:
public:
FixedWingLandingComplexItem
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
FixedWingLandingComplexItem
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
Q_PROPERTY
(
Fact
*
loiterAltitude
READ
loiterAltitude
CONSTANT
)
Q_PROPERTY
(
Fact
*
loiterAltitude
READ
loiterAltitude
CONSTANT
)
Q_PROPERTY
(
Fact
*
loiterRadius
READ
loiterRadius
CONSTANT
)
Q_PROPERTY
(
Fact
*
loiterRadius
READ
loiterRadius
CONSTANT
)
Q_PROPERTY
(
Fact
*
landingAltitude
READ
landingAltitude
CONSTANT
)
Q_PROPERTY
(
Fact
*
landingAltitude
READ
landingAltitude
CONSTANT
)
Q_PROPERTY
(
Fact
*
landing
Distance
READ
landingDistance
CONSTANT
)
Q_PROPERTY
(
Fact
*
landing
Heading
READ
landingHeading
CONSTANT
)
Q_PROPERTY
(
Fact
*
landingHeading
READ
landingHeading
CONSTANT
)
Q_PROPERTY
(
bool
valueSetIsDistance
MEMBER
_valueSetIsDistance
NOTIFY
valueSetIsDistanceChanged
)
Q_PROPERTY
(
Fact
*
fallRate
READ
fallRate
CONSTANT
)
Q_PROPERTY
(
Fact
*
landingDistance
READ
landingDistance
CONSTANT
)
Q_PROPERTY
(
bool
loiterClockwise
MEMBER
_loiterClockwise
NOTIFY
loiterClockwiseChanged
)
Q_PROPERTY
(
Fact
*
glideSlope
READ
glideSlope
CONSTANT
)
Q_PROPERTY
(
bool
loiter
AltitudeRelative
MEMBER
_loiterAltitudeRelative
NOTIFY
loiterAltitudeRelativ
eChanged
)
Q_PROPERTY
(
bool
loiter
Clockwise
MEMBER
_loiterClockwise
NOTIFY
loiterClockwis
eChanged
)
Q_PROPERTY
(
bool
landingAltitudeRelative
MEMBER
_landingAltitudeRelative
NOTIFY
landingAltitud
eRelativeChanged
)
Q_PROPERTY
(
bool
altitudesAreRelative
MEMBER
_altitudesAreRelative
NOTIFY
altitudesAr
eRelativeChanged
)
Q_PROPERTY
(
QGeoCoordinate
loiterCoordinate
READ
loiterCoordinate
WRITE
setLoiterCoordinate
NOTIFY
loiterCoordinateChanged
)
Q_PROPERTY
(
QGeoCoordinate
loiterCoordinate
READ
loiterCoordinate
WRITE
setLoiterCoordinate
NOTIFY
loiterCoordinateChanged
)
Q_PROPERTY
(
QGeoCoordinate
loiterTangentCoordinate
READ
loiterTangentCoordinate
NOTIFY
loiterTangentCoordinateChanged
)
Q_PROPERTY
(
QGeoCoordinate
loiterTangentCoordinate
READ
loiterTangentCoordinate
NOTIFY
loiterTangentCoordinateChanged
)
Q_PROPERTY
(
QGeoCoordinate
landingCoordinate
READ
landingCoordinate
WRITE
setLandingCoordinate
NOTIFY
landingCoordinateChanged
)
Q_PROPERTY
(
QGeoCoordinate
landingCoordinate
READ
landingCoordinate
WRITE
setLandingCoordinate
NOTIFY
landingCoordinateChanged
)
Q_PROPERTY
(
bool
landingCoordSet
MEMBER
_landingCoordSet
NOTIFY
landingCoordSetChanged
)
Q_PROPERTY
(
bool
landingCoordSet
MEMBER
_landingCoordSet
NOTIFY
landingCoordSetChanged
)
Fact
*
loiterAltitude
(
void
)
{
return
&
_loiterAltitudeFact
;
}
Fact
*
loiterAltitude
(
void
)
{
return
&
_loiterAltitudeFact
;
}
Fact
*
loiterRadius
(
void
)
{
return
&
_loiterRadiusFact
;
}
Fact
*
loiterRadius
(
void
)
{
return
&
_loiterRadiusFact
;
}
Fact
*
landingAltitude
(
void
)
{
return
&
_landingAltitudeFact
;
}
Fact
*
landingAltitude
(
void
)
{
return
&
_landingAltitudeFact
;
}
Fact
*
landingDistance
(
void
)
{
return
&
_landingDistanceFact
;
}
Fact
*
landingDistance
(
void
)
{
return
&
_landingDistanceFact
;
}
Fact
*
landingHeading
(
void
)
{
return
&
_landingHeadingFact
;
}
Fact
*
landingHeading
(
void
)
{
return
&
_landingHeadingFact
;
}
Fact
*
fallRate
(
void
)
{
return
&
_fallRat
eFact
;
}
Fact
*
glideSlope
(
void
)
{
return
&
_glideSlop
eFact
;
}
QGeoCoordinate
landingCoordinate
(
void
)
const
{
return
_landingCoordinate
;
}
QGeoCoordinate
landingCoordinate
(
void
)
const
{
return
_landingCoordinate
;
}
QGeoCoordinate
loiterCoordinate
(
void
)
const
{
return
_loiterCoordinate
;
}
QGeoCoordinate
loiterCoordinate
(
void
)
const
{
return
_loiterCoordinate
;
}
QGeoCoordinate
loiterTangentCoordinate
(
void
)
const
{
return
_loiterTangentCoordinate
;
}
QGeoCoordinate
loiterTangentCoordinate
(
void
)
const
{
return
_loiterTangentCoordinate
;
}
...
@@ -81,8 +81,8 @@ public:
...
@@ -81,8 +81,8 @@ public:
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
;
bool
coordinateHasRelativeAltitude
(
void
)
const
final
{
return
_
loiterAltitud
eRelative
;
}
bool
coordinateHasRelativeAltitude
(
void
)
const
final
{
return
_
altitudesAr
eRelative
;
}
bool
exitCoordinateHasRelativeAltitude
(
void
)
const
final
{
return
_
landingAltitud
eRelative
;
}
bool
exitCoordinateHasRelativeAltitude
(
void
)
const
final
{
return
_
altitudesAr
eRelative
;
}
bool
exitCoordinateSameAsEntry
(
void
)
const
final
{
return
false
;
}
bool
exitCoordinateSameAsEntry
(
void
)
const
final
{
return
false
;
}
void
setDirty
(
bool
dirty
)
final
;
void
setDirty
(
bool
dirty
)
final
;
...
@@ -97,7 +97,7 @@ public:
...
@@ -97,7 +97,7 @@ public:
static
const
char
*
loiterRadiusName
;
static
const
char
*
loiterRadiusName
;
static
const
char
*
landingHeadingName
;
static
const
char
*
landingHeadingName
;
static
const
char
*
landingAltitudeName
;
static
const
char
*
landingAltitudeName
;
static
const
char
*
fallRat
eName
;
static
const
char
*
glideSlop
eName
;
signals:
signals:
void
loiterCoordinateChanged
(
QGeoCoordinate
coordinate
);
void
loiterCoordinateChanged
(
QGeoCoordinate
coordinate
);
...
@@ -105,21 +105,23 @@ signals:
...
@@ -105,21 +105,23 @@ signals:
void
landingCoordinateChanged
(
QGeoCoordinate
coordinate
);
void
landingCoordinateChanged
(
QGeoCoordinate
coordinate
);
void
landingCoordSetChanged
(
bool
landingCoordSet
);
void
landingCoordSetChanged
(
bool
landingCoordSet
);
void
loiterClockwiseChanged
(
bool
loiterClockwise
);
void
loiterClockwiseChanged
(
bool
loiterClockwise
);
void
loiterAltitudeRelativeChanged
(
bool
loiterAltitud
eRelative
);
void
altitudesAreRelativeChanged
(
bool
altitudesAr
eRelative
);
void
landingAltitudeRelativeChanged
(
bool
loiterAltitudeRelativ
e
);
void
valueSetIsDistanceChanged
(
bool
valueSetIsDistanc
e
);
private
slots
:
private
slots
:
void
_recalcFromHeadingAndDistanceChange
(
void
);
void
_recalcFromHeadingAndDistanceChange
(
void
);
void
_recalcFromCoordinateChange
(
void
);
void
_recalcFromCoordinateChange
(
void
);
void
_recalcFromRadiusChange
(
void
);
void
_recalcFromRadiusChange
(
void
);
void
_updateLoiterCoodinateAltitudeFromFact
(
void
);
void
_updateLoiterCoodinateAltitudeFromFact
(
void
);
void
_updateLandingCoodinateAltitudeFromFact
(
void
);
void
_updateLandingCoodinateAltitudeFromFact
(
void
);
double
_mathematicAngleToHeading
(
double
angle
);
double
_mathematicAngleToHeading
(
double
angle
);
double
_headingToMathematicAngle
(
double
heading
);
double
_headingToMathematicAngle
(
double
heading
);
void
_setDirty
(
void
);
void
_setDirty
(
void
);
void
_glideSlopeChanged
(
void
);
private:
private:
QPointF
_rotatePoint
(
const
QPointF
&
point
,
const
QPointF
&
origin
,
double
angle
);
QPointF
_rotatePoint
(
const
QPointF
&
point
,
const
QPointF
&
origin
,
double
angle
);
void
_calcGlideSlope
(
void
);
int
_sequenceNumber
;
int
_sequenceNumber
;
bool
_dirty
;
bool
_dirty
;
...
@@ -136,18 +138,22 @@ private:
...
@@ -136,18 +138,22 @@ private:
Fact
_loiterRadiusFact
;
Fact
_loiterRadiusFact
;
Fact
_landingHeadingFact
;
Fact
_landingHeadingFact
;
Fact
_landingAltitudeFact
;
Fact
_landingAltitudeFact
;
Fact
_
fallRat
eFact
;
Fact
_
glideSlop
eFact
;
bool
_loiterClockwise
;
bool
_loiterClockwise
;
bool
_
loiterAltitud
eRelative
;
bool
_
altitudesAr
eRelative
;
bool
_
landingAltitudeRelativ
e
;
bool
_
valueSetIsDistanc
e
;
static
const
char
*
_jsonLoiterCoordinateKey
;
static
const
char
*
_jsonLoiterCoordinateKey
;
static
const
char
*
_jsonLoiterRadiusKey
;
static
const
char
*
_jsonLoiterRadiusKey
;
static
const
char
*
_jsonLoiterClockwiseKey
;
static
const
char
*
_jsonLoiterClockwiseKey
;
static
const
char
*
_jsonLoiterAltitudeRelativeKey
;
static
const
char
*
_jsonLandingCoordinateKey
;
static
const
char
*
_jsonLandingCoordinateKey
;
static
const
char
*
_jsonValueSetIsDistanceKey
;
static
const
char
*
_jsonAltitudesAreRelativeKey
;
// Only in older file formats
static
const
char
*
_jsonLandingAltitudeRelativeKey
;
static
const
char
*
_jsonLandingAltitudeRelativeKey
;
static
const
char
*
_jsonLoiterAltitudeRelativeKey
;
static
const
char
*
_jsonFallRateKey
;
static
const
char
*
_jsonFallRateKey
;
};
};
...
...
src/PlanView/FWLandingPatternEditor.qml
View file @
1ac6cd32
...
@@ -34,6 +34,8 @@ Rectangle {
...
@@ -34,6 +34,8 @@ Rectangle {
property
real
_margin
:
ScreenTools
.
defaultFontPixelWidth
/
2
property
real
_margin
:
ScreenTools
.
defaultFontPixelWidth
/
2
property
real
_spacer
:
ScreenTools
.
defaultFontPixelWidth
/
2
property
real
_spacer
:
ScreenTools
.
defaultFontPixelWidth
/
2
ExclusiveGroup
{
id
:
distanceGlideGroup
}
Column
{
Column
{
id
:
editorColumn
id
:
editorColumn
anchors.margins
:
_margin
anchors.margins
:
_margin
...
@@ -58,17 +60,6 @@ Rectangle {
...
@@ -58,17 +60,6 @@ Rectangle {
Item
{
width
:
1
;
height
:
_spacer
}
Item
{
width
:
1
;
height
:
_spacer
}
QGCCheckBox
{
QGCCheckBox
{
id
:
loiterAltRelative
anchors.right
:
parent
.
right
text
:
qsTr
(
"
Altitude relative to home
"
)
checked
:
missionItem
.
loiterAltitudeRelative
onClicked
:
missionItem
.
loiterAltitudeRelative
=
checked
}
Item
{
width
:
1
;
height
:
_spacer
}
QGCCheckBox
{
anchors.left
:
loiterAltRelative
.
left
text
:
qsTr
(
"
Loiter clockwise
"
)
text
:
qsTr
(
"
Loiter clockwise
"
)
checked
:
missionItem
.
loiterClockwise
checked
:
missionItem
.
loiterClockwise
onClicked
:
missionItem
.
loiterClockwise
=
checked
onClicked
:
missionItem
.
loiterClockwise
=
checked
...
@@ -98,53 +89,33 @@ Rectangle {
...
@@ -98,53 +89,33 @@ Rectangle {
}
}
QGCRadioButton
{
QGCRadioButton
{
id
:
useLandingDistance
id
:
specifyLandingDistance
text
:
qsTr
(
"
Landing dist
"
)
text
:
qsTr
(
"
Landing Dist
"
)
checked
:
!
useFallRate
.
checked
checked
:
missionItem
.
valueSetIsDistance
onClicked
:
{
exclusiveGroup
:
distanceGlideGroup
useFallRate
.
checked
=
false
onClicked
:
missionItem
.
valueSetIsDistance
=
checked
missionItem
.
fallRate
.
value
=
parseFloat
(
missionItem
.
loiterAltitude
.
value
)
*
100
/
parseFloat
(
missionItem
.
landingDistance
.
value
)
Layout.fillWidth
:
true
}
Layout.fillWidth
:
true
}
}
FactTextField
{
FactTextField
{
fact
:
missionItem
.
landingDistance
fact
:
missionItem
.
landingDistance
enabled
:
use
LandingDistance
.
checked
enabled
:
specify
LandingDistance
.
checked
Layout.fillWidth
:
true
Layout.fillWidth
:
true
}
}
QGCRadioButton
{
QGCRadioButton
{
id
:
useFallRate
id
:
specifyGlideSlope
text
:
qsTr
(
"
Descent rate
"
)
text
:
qsTr
(
"
Glide Slope
"
)
checked
:
!
useLandingDistance
.
checked
checked
:
!
missionItem
.
valueSetIsDistance
onClicked
:
{
exclusiveGroup
:
distanceGlideGroup
useLandingDistance
.
checked
=
false
onClicked
:
missionItem
.
valueSetIsDistance
=
checked
missionItem
.
landingDistance
.
value
=
parseFloat
(
missionItem
.
loiterAltitude
.
value
)
*
100
/
parseFloat
(
missionItem
.
fallRate
.
value
)
Layout.fillWidth
:
true
}
Layout.fillWidth
:
true
}
}
FactTextField
{
FactTextField
{
fact
:
missionItem
.
fallRate
fact
:
missionItem
.
glideSlope
enabled
:
useFallRate
.
checked
enabled
:
specifyGlideSlope
.
checked
Layout.fillWidth
:
true
Layout.fillWidth
:
true
}
Connections
{
target
:
missionItem
.
landingDistance
onValueChanged
:
{
missionItem
.
fallRate
.
value
=
parseFloat
(
missionItem
.
loiterAltitude
.
value
)
*
100
/
parseFloat
(
missionItem
.
landingDistance
.
value
)
}
}
Connections
{
target
:
missionItem
.
fallRate
onValueChanged
:
{
missionItem
.
landingDistance
.
value
=
parseFloat
(
missionItem
.
loiterAltitude
.
value
)
*
100
/
parseFloat
(
missionItem
.
fallRate
.
value
)
}
}
}
}
}
...
@@ -152,9 +123,9 @@ Rectangle {
...
@@ -152,9 +123,9 @@ Rectangle {
QGCCheckBox
{
QGCCheckBox
{
anchors.right
:
parent
.
right
anchors.right
:
parent
.
right
text
:
qsTr
(
"
Altitude relative to home
"
)
text
:
qsTr
(
"
Altitude
s
relative to home
"
)
checked
:
missionItem
.
landingAltitud
eRelative
checked
:
missionItem
.
altitudesAr
eRelative
onClicked
:
missionItem
.
landingAltitud
eRelative
=
checked
onClicked
:
missionItem
.
altitudesAr
eRelative
=
checked
}
}
}
}
...
...
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