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
e163d336
Commit
e163d336
authored
Jun 20, 2018
by
Gus Grubba
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'master' of
https://github.com/mavlink/qgroundcontrol
into syncRework
parents
70fced38
4dc7b9d6
Changes
23
Hide whitespace changes
Inline
Side-by-side
Showing
23 changed files
with
341 additions
and
167 deletions
+341
-167
v2.0
libs/mavlink/include/mavlink/v2.0
+1
-1
FirmwarePlugin.cc
src/FirmwarePlugin/FirmwarePlugin.cc
+0
-6
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+0
-4
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+1
-19
PX4FirmwarePlugin.h
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
+0
-1
FlightDisplayView.qml
src/FlightDisplay/FlightDisplayView.qml
+5
-27
FlightDisplayViewMap.qml
src/FlightDisplay/FlightDisplayViewMap.qml
+91
-14
GuidedActionConfirm.qml
src/FlightDisplay/GuidedActionConfirm.qml
+3
-2
GuidedActionsController.qml
src/FlightDisplay/GuidedActionsController.qml
+24
-11
GuidedAltitudeSlider.qml
src/FlightDisplay/GuidedAltitudeSlider.qml
+2
-1
MissionItemIndicatorDrag.qml
src/FlightMap/MapItems/MissionItemIndicatorDrag.qml
+2
-1
PlanManager.cc
src/MissionManager/PlanManager.cc
+4
-4
QGCMapCircleVisuals.qml
src/MissionManager/QGCMapCircleVisuals.qml
+73
-34
StructureScanComplexItem.cc
src/MissionManager/StructureScanComplexItem.cc
+14
-8
StructureScanComplexItem.h
src/MissionManager/StructureScanComplexItem.h
+1
-1
StructureScanComplexItemTest.cc
src/MissionManager/StructureScanComplexItemTest.cc
+1
-1
MissionItemStatus.qml
src/PlanView/MissionItemStatus.qml
+2
-0
QGCApplication.cc
src/QGCApplication.cc
+2
-0
DropPanel.qml
src/QmlControls/DropPanel.qml
+0
-2
MissionItemIndexLabel.qml
src/QmlControls/MissionItemIndexLabel.qml
+1
-1
Vehicle.cc
src/Vehicle/Vehicle.cc
+100
-21
Vehicle.h
src/Vehicle/Vehicle.h
+10
-8
QGCXPlaneLink.cc
src/comm/QGCXPlaneLink.cc
+4
-0
No files found.
v2.0
@
f5c0ba68
Subproject commit
033fa8e7a4a75a0c3f17cea57e3be8966e05f770
Subproject commit
f5c0ba684659fbc6c6c5f8777bd30e0b3c32fdef
src/FirmwarePlugin/FirmwarePlugin.cc
View file @
e163d336
...
...
@@ -270,12 +270,6 @@ void FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel)
qgcApp
()
->
showMessage
(
guided_mode_not_supported_by_vehicle
);
}
void
FirmwarePlugin
::
guidedModeOrbit
(
Vehicle
*
/*vehicle*/
,
const
QGeoCoordinate
&
/*centerCoord*/
,
double
/*radius*/
,
double
/*velocity*/
,
double
/*altitude*/
)
{
// Not supported by generic vehicle
qgcApp
()
->
showMessage
(
guided_mode_not_supported_by_vehicle
);
}
void
FirmwarePlugin
::
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
{
// Not supported by generic vehicle
...
...
src/FirmwarePlugin/FirmwarePlugin.h
View file @
e163d336
...
...
@@ -136,10 +136,6 @@ public:
/// Command the vehicle to start the mission
virtual
void
startMission
(
Vehicle
*
vehicle
);
/// Command vehicle to orbit given center point
/// @param centerCoord Center Coordinates
virtual
void
guidedModeOrbit
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
centerCoord
,
double
radius
,
double
velocity
,
double
altitude
);
/// Command vehicle to move to specified location (altitude is included and relative)
virtual
void
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
);
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
e163d336
...
...
@@ -232,7 +232,7 @@ bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities c
{
int
available
=
SetFlightModeCapability
|
PauseVehicleCapability
|
GuidedModeCapability
;
if
(
vehicle
->
multiRotor
()
||
vehicle
->
vtol
())
{
available
|=
TakeoffVehicleCapability
;
available
|=
TakeoffVehicleCapability
|
OrbitModeCapability
;
}
return
(
capabilities
&
available
)
==
capabilities
;
...
...
@@ -364,24 +364,6 @@ void PX4FirmwarePlugin::guidedModeLand(Vehicle* vehicle)
_setFlightModeAndValidate
(
vehicle
,
_landingFlightMode
);
}
void
PX4FirmwarePlugin
::
guidedModeOrbit
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
centerCoord
,
double
radius
,
double
velocity
,
double
altitude
)
{
if
(
!
isGuidedMode
(
vehicle
))
{
setGuidedMode
(
vehicle
,
true
);
}
vehicle
->
sendMavCommand
(
vehicle
->
defaultComponentId
(),
MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE
,
true
,
// show error if fails
radius
,
velocity
,
altitude
,
NAN
,
centerCoord
.
isValid
()
?
centerCoord
.
latitude
()
:
NAN
,
centerCoord
.
isValid
()
?
centerCoord
.
longitude
()
:
NAN
,
centerCoord
.
isValid
()
?
centerCoord
.
altitude
()
:
NAN
);
}
void
PX4FirmwarePlugin
::
_mavCommandResult
(
int
vehicleId
,
int
component
,
int
command
,
int
result
,
bool
noReponseFromVehicle
)
{
Q_UNUSED
(
vehicleId
);
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
View file @
e163d336
...
...
@@ -46,7 +46,6 @@ public:
void
guidedModeRTL
(
Vehicle
*
vehicle
)
override
;
void
guidedModeLand
(
Vehicle
*
vehicle
)
override
;
void
guidedModeTakeoff
(
Vehicle
*
vehicle
,
double
takeoffAltRel
)
override
;
void
guidedModeOrbit
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
centerCoord
=
QGeoCoordinate
(),
double
radius
=
NAN
,
double
velocity
=
NAN
,
double
altitude
=
NAN
)
override
;
void
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
override
;
void
guidedModeChangeAltitude
(
Vehicle
*
vehicle
,
double
altitudeRel
)
override
;
double
minimumTakeoffAltitude
(
Vehicle
*
vehicle
)
override
;
...
...
src/FlightDisplay/FlightDisplayView.qml
View file @
e163d336
...
...
@@ -508,11 +508,10 @@ QGCView {
z
:
_panel
.
z
+
4
title
:
qsTr
(
"
Fly
"
)
maxHeight
:
(
_flightVideo
.
visible
?
_flightVideo
.
y
:
parent
.
height
)
-
toolStrip
.
y
buttonVisible
:
[
_useChecklist
,
_guidedController
.
showTakeoff
||
!
_guidedController
.
showLand
,
_guidedController
.
showLand
&&
!
_guidedController
.
showTakeoff
,
true
,
true
,
true
,
_guidedController
.
smartShotsAvailable
]
buttonEnabled
:
[
_useChecklist
&&
_activeVehicle
,
_guidedController
.
showTakeoff
,
_guidedController
.
showLand
,
_guidedController
.
showRTL
,
_guidedController
.
showPause
,
_anyActionAvailable
,
_anySmartShotAvailable
]
buttonVisible
:
[
_useChecklist
,
_guidedController
.
showTakeoff
||
!
_guidedController
.
showLand
,
_guidedController
.
showLand
&&
!
_guidedController
.
showTakeoff
,
true
,
true
,
true
]
buttonEnabled
:
[
_useChecklist
&&
_activeVehicle
,
_guidedController
.
showTakeoff
,
_guidedController
.
showLand
,
_guidedController
.
showRTL
,
_guidedController
.
showPause
,
_anyActionAvailable
]
property
bool
_anyActionAvailable
:
_guidedController
.
showStartMission
||
_guidedController
.
showResumeMission
||
_guidedController
.
showChangeAlt
||
_guidedController
.
showLandAbort
property
bool
_anySmartShotAvailable
:
_guidedController
.
showOrbit
property
var
_actionModel
:
[
{
title
:
_guidedController
.
startMissionTitle
,
...
...
@@ -545,14 +544,6 @@ QGCView {
visible
:
_guidedController
.
showLandAbort
}
]
property
var
_smartShotModel
:
[
{
title
:
_guidedController
.
orbitTitle
,
text
:
_guidedController
.
orbitMessage
,
action
:
_guidedController
.
actionOrbit
,
visible
:
_guidedController
.
showOrbit
}
]
model
:
[
{
...
...
@@ -584,28 +575,15 @@ QGCView {
name
:
qsTr
(
"
Action
"
),
iconSource
:
"
/res/action.svg
"
,
action
:
-
1
},
/*
No firmware support any smart shots yet
{
name: qsTr("Smart"),
iconSource: "/qmlimages/MapCenter.svg",
action: -1
},
*/
}
]
onClicked
:
{
guidedActionsController
.
closeAll
()
var
action
=
model
[
index
].
action
if
(
action
===
-
1
)
{
if
(
index
==
5
)
{
guidedActionList
.
model
=
_actionModel
guidedActionList
.
visible
=
true
}
else
if
(
index
==
6
)
{
guidedActionList
.
model
=
_smartShotModel
guidedActionList
.
visible
=
true
}
guidedActionList
.
model
=
_actionModel
guidedActionList
.
visible
=
true
}
else
{
_guidedController
.
confirmAction
(
action
)
}
...
...
src/FlightDisplay/FlightDisplayViewMap.qml
View file @
e163d336
...
...
@@ -49,7 +49,6 @@ FlightMap {
property
var
_rallyPointController
:
_planMasterController
.
rallyPointController
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
property
var
_activeVehicleCoordinate
:
_activeVehicle
?
_activeVehicle
.
coordinate
:
QtPositioning
.
coordinate
()
property
var
_gotoHereCoordinate
:
QtPositioning
.
coordinate
()
property
real
_toolButtonTopMargin
:
parent
.
height
-
ScreenTools
.
availableHeight
+
(
ScreenTools
.
defaultFontPixelHeight
/
2
)
property
bool
_disableVehicleTracking
:
false
...
...
@@ -264,10 +263,19 @@ FlightMap {
}
}
// GoTo here waypoint
// Camera trigger points
MapItemView
{
model
:
_activeVehicle
?
_activeVehicle
.
cameraTriggerPoints
:
0
delegate
:
CameraTriggerIndicator
{
coordinate
:
object
.
coordinate
z
:
QGroundControl
.
zOrderTopMost
}
}
MapQuickItem
{
coordinate
:
_gotoHereCoordinate
visible
:
_activeVehicle
&&
_activeVehicle
.
guidedModeSupported
&&
_gotoHereCoordinate
.
isValid
id
:
gotoLocationItem
visible
:
false
z
:
QGroundControl
.
zOrderMapItems
anchorPoint.x
:
sourceItem
.
anchorPointX
anchorPoint.y
:
sourceItem
.
anchorPointY
...
...
@@ -277,15 +285,44 @@ FlightMap {
index
:
-
1
label
:
qsTr
(
"
Goto here
"
,
"
Goto here waypoint
"
)
}
}
// Camera trigger points
MapItemView
{
model
:
_activeVehicle
?
_activeVehicle
.
cameraTriggerPoints
:
0
function
show
(
coord
)
{
gotoLocationItem
.
coordinate
=
coord
gotoLocationItem
.
visible
=
true
}
delegate
:
CameraTriggerIndicator
{
coordinate
:
object
.
coordinate
z
:
QGroundControl
.
zOrderTopMost
function
hide
()
{
gotoLocationItem
.
visible
=
false
}
}
QGCMapCircleVisuals
{
id
:
orbitMapCircle
mapControl
:
parent
mapCircle
:
_mapCircle
visible
:
false
property
alias
center
:
_mapCircle
.
center
property
real
radius
:
defaultRadius
readonly
property
real
defaultRadius
:
30
function
show
(
coord
)
{
orbitMapCircle
.
radius
=
defaultRadius
orbitMapCircle
.
center
=
coord
orbitMapCircle
.
visible
=
true
}
function
hide
()
{
orbitMapCircle
.
visible
=
false
}
Component.onCompleted
:
guidedActionsController
.
orbitMapCircle
=
orbitMapCircle
QGCMapCircle
{
id
:
_mapCircle
interactive
:
true
radius.rawValue
:
orbitMapCircle
.
radius
}
}
...
...
@@ -293,10 +330,50 @@ FlightMap {
MouseArea
{
anchors.fill
:
parent
Menu
{
id
:
clickMenu
property
var
coord
MenuItem
{
text
:
qsTr
(
"
Go to location
"
)
visible
:
guidedActionsController
.
showGotoLocation
onTriggered
:
{
gotoLocationItem
.
show
(
clickMenu
.
coord
)
orbitMapCircle
.
hide
()
guidedActionsController
.
confirmAction
(
guidedActionsController
.
actionGoto
,
clickMenu
.
coord
)
}
}
MenuItem
{
text
:
qsTr
(
"
Orbit at location
"
)
visible
:
guidedActionsController
.
showOrbit
onTriggered
:
{
orbitMapCircle
.
show
(
clickMenu
.
coord
)
gotoLocationItem
.
hide
()
guidedActionsController
.
confirmAction
(
guidedActionsController
.
actionOrbit
,
clickMenu
.
coord
)
}
}
}
onClicked
:
{
if
(
guidedActionsController
.
showGotoLocation
&&
!
guidedActionsController
.
guidedUIVisible
)
{
_gotoHereCoordinate
=
flightMap
.
toCoordinate
(
Qt
.
point
(
mouse
.
x
,
mouse
.
y
),
false
/* clipToViewPort */
)
guidedActionsController
.
confirmAction
(
guidedActionsController
.
actionGoto
,
_gotoHereCoordinate
)
if
(
guidedActionsController
.
guidedUIVisible
||
(
!
guidedActionsController
.
showGotoLocation
&&
!
guidedActionsController
.
showOrbit
))
{
return
}
orbitMapCircle
.
hide
()
gotoLocationItem
.
hide
()
var
clickCoord
=
flightMap
.
toCoordinate
(
Qt
.
point
(
mouse
.
x
,
mouse
.
y
),
false
/* clipToViewPort */
)
if
(
guidedActionsController
.
showGotoLocation
&&
guidedActionsController
.
showOrbit
)
{
clickMenu
.
coord
=
clickCoord
clickMenu
.
popup
()
}
else
if
(
guidedActionsController
.
showGotoLocation
)
{
_guidedLocationCoordinate
=
clickCoord
guidedActionsController
.
confirmAction
(
guidedActionsController
.
actionGoto
,
clickCoord
)
}
else
if
(
guidedActionsController
.
showOrbit
)
{
orbitMapCircle
.
show
(
clickCoord
)
guidedActionsController
.
confirmAction
(
guidedActionsController
.
actionOrbit
,
clickCoord
)
}
}
}
...
...
src/FlightDisplay/GuidedActionConfirm.qml
View file @
e163d336
...
...
@@ -100,12 +100,13 @@ Rectangle {
onAccept
:
{
_root
.
visible
=
false
var
altitudeChange
=
0
if
(
altitudeSlider
.
visible
)
{
_root
.
actionData
=
altitudeSlider
.
get
Value
()
altitudeChange
=
altitudeSlider
.
getAltitudeChange
Value
()
altitudeSlider
.
visible
=
false
}
hideTrigger
=
false
guidedController
.
executeAction
(
_root
.
action
,
_root
.
actionData
)
guidedController
.
executeAction
(
_root
.
action
,
_root
.
actionData
,
altitudeChange
)
}
onReject
:
{
...
...
src/FlightDisplay/GuidedActionsController.qml
View file @
e163d336
...
...
@@ -31,6 +31,7 @@ Item {
property
var
confirmDialog
property
var
actionList
property
var
altitudeSlider
property
var
orbitMapCircle
readonly
property
string
emergencyStopTitle
:
qsTr
(
"
EMERGENCY STOP
"
)
readonly
property
string
armTitle
:
qsTr
(
"
Arm
"
)
...
...
@@ -62,9 +63,9 @@ Item {
readonly
property
string
landMessage
:
qsTr
(
"
Land the vehicle at the current position.
"
)
readonly
property
string
rtlMessage
:
qsTr
(
"
Return to the home position of the vehicle.
"
)
readonly
property
string
changeAltMessage
:
qsTr
(
"
Change the altitude of the vehicle up or down.
"
)
readonly
property
string
gotoMessage
:
qsTr
(
"
Move the vehicle to the
location clicked on the map
.
"
)
readonly
property
string
gotoMessage
:
qsTr
(
"
Move the vehicle to the
specified location
.
"
)
property
string
setWaypointMessage
:
qsTr
(
"
Adjust current waypoint to %1.
"
).
arg
(
_actionData
)
readonly
property
string
orbitMessage
:
qsTr
(
"
Orbit the vehicle around the
current location.
"
)
readonly
property
string
orbitMessage
:
qsTr
(
"
Orbit the vehicle around the
specified location. Warning: WORK IN PROGRESS!
"
)
readonly
property
string
landAbortMessage
:
qsTr
(
"
Abort the landing sequence.
"
)
readonly
property
string
pauseMessage
:
qsTr
(
"
Pause the vehicle at it's current position, adjusting altitude up or down as needed.
"
)
readonly
property
string
mvPauseMessage
:
qsTr
(
"
Pause all vehicles at their current position.
"
)
...
...
@@ -103,7 +104,7 @@ Item {
property
bool
showContinueMission
:
_guidedActionsEnabled
&&
_missionAvailable
&&
!
_missionActive
&&
_vehicleFlying
&&
(
_currentMissionIndex
<
missionController
.
visualItems
.
count
-
1
)
property
bool
showPause
:
_guidedActionsEnabled
&&
_vehicleArmed
&&
_activeVehicle
.
pauseVehicleSupported
&&
_vehicleFlying
&&
!
_vehiclePaused
property
bool
showChangeAlt
:
_guidedActionsEnabled
&&
_vehicleFlying
&&
_activeVehicle
.
guidedModeSupported
&&
_vehicleArmed
&&
!
_missionActive
property
bool
showOrbit
:
_guidedActionsEnabled
&&
!
_hideOrbit
&&
_vehicleFlying
&&
_activeVehicle
.
orbitModeSupported
&&
_vehicleArmed
&&
!
_missionActive
property
bool
showOrbit
:
_guidedActionsEnabled
&&
!
_hideOrbit
&&
_vehicleFlying
&&
_activeVehicle
.
orbitModeSupported
&&
!
_missionActive
property
bool
showLandAbort
:
_guidedActionsEnabled
&&
_vehicleFlying
&&
_activeVehicle
.
fixedWing
&&
_vehicleLanding
property
bool
showGotoLocation
:
_guidedActionsEnabled
&&
_vehicleFlying
...
...
@@ -152,8 +153,16 @@ Item {
on__GuidedModeSupportedChanged
:
_outputState
()
on__PauseVehicleSupportedChanged
:
_outputState
()
on_CurrentMissionIndexChanged
:
console
.
log
(
"
_currentMissionIndex
"
,
_currentMissionIndex
)
on_ResumeMissionIndexChanged
:
console
.
log
(
"
_resumeMissionIndex
"
,
_resumeMissionIndex
)
on_CurrentMissionIndexChanged
:
{
if
(
__debugGuidedStates
)
{
console
.
log
(
"
_currentMissionIndex
"
,
_currentMissionIndex
)
}
}
on_ResumeMissionIndexChanged
:
{
if
(
__debugGuidedStates
)
{
console
.
log
(
"
_resumeMissionIndex
"
,
_resumeMissionIndex
)
}
}
onShowResumeMissionChanged
:
{
if
(
__debugGuidedStates
)
{
console
.
log
(
"
showResumeMission
"
,
showResumeMission
)
...
...
@@ -182,7 +191,8 @@ Item {
_vehicleWasFlying
=
true
}
}
property
var
_actionData
property
var
_actionData
on_FlightModeChanged
:
{
_vehiclePaused
=
_activeVehicle
?
_flightMode
===
_activeVehicle
.
pauseFlightMode
:
false
...
...
@@ -291,6 +301,8 @@ Item {
confirmDialog
.
title
=
orbitTitle
confirmDialog
.
message
=
orbitMessage
confirmDialog
.
hideTrigger
=
Qt
.
binding
(
function
()
{
return
!
showOrbit
})
altitudeSlider
.
reset
()
altitudeSlider
.
visible
=
true
break
;
case
actionLandAbort
:
confirmDialog
.
title
=
landAbortTitle
...
...
@@ -327,7 +339,7 @@ Item {
}
// Executes the specified action
function
executeAction
(
actionCode
,
actionData
)
{
function
executeAction
(
actionCode
,
actionData
,
actionAltitudeChange
)
{
var
i
;
var
rgVehicle
;
switch
(
actionCode
)
{
...
...
@@ -338,7 +350,7 @@ Item {
_activeVehicle
.
guidedModeLand
()
break
case
actionTakeoff
:
_activeVehicle
.
guidedModeTakeoff
(
action
Data
)
_activeVehicle
.
guidedModeTakeoff
(
action
AltitudeChange
)
break
case
actionResumeMission
:
case
actionResumeMissionUploadFail
:
...
...
@@ -368,7 +380,7 @@ Item {
_activeVehicle
.
emergencyStop
()
break
case
actionChangeAlt
:
_activeVehicle
.
guidedModeChangeAltitude
(
action
Data
)
_activeVehicle
.
guidedModeChangeAltitude
(
action
AltitudeChange
)
break
case
actionGoto
:
_activeVehicle
.
guidedModeGotoLocation
(
actionData
)
...
...
@@ -377,14 +389,15 @@ Item {
_activeVehicle
.
setCurrentMissionSequence
(
actionData
)
break
case
actionOrbit
:
_activeVehicle
.
guidedModeOrbit
()
_activeVehicle
.
guidedModeOrbit
(
orbitMapCircle
.
center
,
orbitMapCircle
.
radius
,
_activeVehicle
.
altitudeAMSL
+
actionAltitudeChange
)
orbitMapCircle
.
hide
()
break
case
actionLandAbort
:
_activeVehicle
.
abortLanding
(
50
)
// hardcoded value for climbOutAltitude that is currently ignored
break
case
actionPause
:
_activeVehicle
.
pauseVehicle
()
_activeVehicle
.
guidedModeChangeAltitude
(
action
Data
)
_activeVehicle
.
guidedModeChangeAltitude
(
action
AltitudeChange
)
break
case
actionMVPause
:
rgVehicle
=
QGroundControl
.
multiVehicleManager
.
vehicles
...
...
src/FlightDisplay/GuidedAltitudeSlider.qml
View file @
e163d336
...
...
@@ -36,7 +36,8 @@ Rectangle {
altField
.
setToMinimumTakeoff
()
}
function
getValue
()
{
/// Returns the user specified change in altitude from the current vehicle altitude
function
getAltitudeChangeValue
()
{
return
altField
.
newAltitudeMeters
-
_vehicleAltitude
}
...
...
src/FlightMap/MapItems/MissionItemIndicatorDrag.qml
View file @
e163d336
...
...
@@ -25,6 +25,7 @@ Rectangle {
z
:
QGroundControl
.
zOrderMapItems
+
1
// Above item icons
// Properties which must be specific by consumer
property
var
mapControl
///< Map control which contains this item
property
var
itemIndicator
///< The mission item indicator to drag around
property
var
itemCoordinate
///< Coordinate we are updating during drag
...
...
@@ -51,7 +52,7 @@ Rectangle {
function
liveDrag
()
{
if
(
!
itemDragger
.
_preventCoordinateBindingLoop
&&
itemDrag
.
drag
.
active
)
{
var
point
=
Qt
.
point
(
itemDragger
.
x
+
_touchMarginHorizontal
+
itemIndicator
.
anchorPoint
.
x
,
itemDragger
.
y
+
_touchMarginVertical
+
itemIndicator
.
anchorPoint
.
y
)
var
coordinate
=
map
.
toCoordinate
(
point
,
false
/* clipToViewPort */
)
var
coordinate
=
map
Control
.
toCoordinate
(
point
,
false
/* clipToViewPort */
)
itemDragger
.
_preventCoordinateBindingLoop
=
true
coordinate
.
altitude
=
itemCoordinate
.
altitude
itemCoordinate
=
coordinate
...
...
src/MissionManager/PlanManager.cc
View file @
e163d336
...
...
@@ -392,8 +392,8 @@ void PlanManager::_handleMissionItem(const mavlink_message_t& message, bool miss
mavlink_msg_mission_item_int_decode
(
&
message
,
&
missionItem
);
command
=
(
MAV_CMD
)
missionItem
.
command
,
frame
=
(
MAV_FRAME
)
missionItem
.
frame
,
param1
=
missionItem
.
param1
;
frame
=
(
MAV_FRAME
)
missionItem
.
frame
,
param1
=
missionItem
.
param1
;
param2
=
missionItem
.
param2
;
param3
=
missionItem
.
param3
;
param4
=
missionItem
.
param4
;
...
...
@@ -408,8 +408,8 @@ void PlanManager::_handleMissionItem(const mavlink_message_t& message, bool miss
mavlink_msg_mission_item_decode
(
&
message
,
&
missionItem
);
command
=
(
MAV_CMD
)
missionItem
.
command
,
frame
=
(
MAV_FRAME
)
missionItem
.
frame
,
param1
=
missionItem
.
param1
;
frame
=
(
MAV_FRAME
)
missionItem
.
frame
,
param1
=
missionItem
.
param1
;
param2
=
missionItem
.
param2
;
param3
=
missionItem
.
param3
;
param4
=
missionItem
.
param4
;
...
...
src/MissionManager/QGCMapCircleVisuals.qml
View file @
e163d336
...
...
@@ -27,52 +27,60 @@ Item {
property
bool
interactive
:
mapCircle
.
interactive
/// true: user can manipulate polygon
property
color
interiorColor
:
"
transparent
"
property
real
interiorOpacity
:
1
property
int
borderWidth
:
0
property
color
borderColor
:
"
black
"
property
int
borderWidth
:
2
property
color
borderColor
:
"
orange
"
property
var
_circleComponent
property
var
_
centerDragHandle
Component
property
var
_
dragHandles
Component
function
addVisuals
()
{
_circleComponent
=
circleComponent
.
createObject
(
mapControl
)
mapControl
.
addMapItem
(
_circleComponent
)
if
(
!
_circleComponent
)
{
_circleComponent
=
circleComponent
.
createObject
(
mapControl
)
mapControl
.
addMapItem
(
_circleComponent
)
}
}
function
removeVisuals
()
{
_circleComponent
.
destroy
()
if
(
_circleComponent
)
{
_circleComponent
.
destroy
()
_circleComponent
=
undefined
}
}
function
addHandles
()
{
if
(
!
_
centerDragHandle
Component
)
{
_
centerDragHandleComponent
=
centerDragHandle
Component
.
createObject
(
mapControl
)
function
add
Drag
Handles
()
{
if
(
!
_
dragHandles
Component
)
{
_
dragHandlesComponent
=
dragHandles
Component
.
createObject
(
mapControl
)
}
}
function
removeHandles
()
{
if
(
_
centerDragHandle
Component
)
{
_
centerDragHandle
Component
.
destroy
()
_
centerDragHandle
Component
=
undefined
function
remove
Drag
Handles
()
{
if
(
_
dragHandles
Component
)
{
_
dragHandles
Component
.
destroy
()
_
dragHandles
Component
=
undefined
}
}
onInteractiveChanged
:
{
if
(
interactive
)
{
addHandles
()
function
updateInternalComponents
()
{
if
(
visible
)
{
addVisuals
()
if
(
interactive
)
{
addDragHandles
()
}
else
{
removeDragHandles
()
}
}
else
{
removeHandles
()
removeVisuals
()
removeDragHandles
()
}
}
Component.onCompleted
:
{
addVisuals
()
if
(
interactive
)
{
addHandles
()
}
}
Component.onCompleted
:
updateInternalComponents
()
onInteractiveChanged
:
updateInternalComponents
()
onVisibleChanged
:
updateInternalComponents
()
Component.onDestruction
:
{
removeVisuals
()
removeHandles
()
remove
Drag
Handles
()
}
Component
{
...
...
@@ -112,27 +120,58 @@ Item {
id
:
centerDragAreaComponent
MissionItemIndicatorDrag
{
onItemCoordinateChanged
:
mapCircle
.
center
=
itemCoordinate
mapControl
:
_root
.
mapControl
onItemCoordinateChanged
:
mapCircle
.
center
=
itemCoordinate
}
}
Component
{
id
:
centerDragHandleComponent
id
:
radiusDragAreaComponent
MissionItemIndicatorDrag
{
mapControl
:
_root
.
mapControl
onItemCoordinateChanged
:
mapCircle
.
radius
.
rawValue
=
mapCircle
.
center
.
distanceTo
(
itemCoordinate
)
}
}
Component
{
id
:
dragHandlesComponent
Item
{
property
var
dragHandle
property
var
dragArea
property
var
centerDragHandle
property
var
centerDragArea
property
var
radiusDragHandle
property
var
radiusDragArea
property
var
radiusDragCoord
:
QtPositioning
.
coordinate
()
property
var
circleCenterCoord
:
mapCircle
.
center
property
real
circleRadius
:
mapCircle
.
radius
.
rawValue
function
calcRadiusDragCoord
()
{
radiusDragCoord
=
mapCircle
.
center
.
atDistanceAndAzimuth
(
circleRadius
,
90
)
}
onCircleCenterCoordChanged
:
calcRadiusDragCoord
()
onCircleRadiusChanged
:
calcRadiusDragCoord
()
Component.onCompleted
:
{
dragHandle
=
dragHandleComponent
.
createObject
(
mapControl
)
dragHandle
.
coordinate
=
Qt
.
binding
(
function
()
{
return
mapCircle
.
center
})
mapControl
.
addMapItem
(
dragHandle
)
dragArea
=
centerDragAreaComponent
.
createObject
(
mapControl
,
{
"
itemIndicator
"
:
dragHandle
,
"
itemCoordinate
"
:
mapCircle
.
center
})
calcRadiusDragCoord
()
radiusDragHandle
=
dragHandleComponent
.
createObject
(
mapControl
)
radiusDragHandle
.
coordinate
=
Qt
.
binding
(
function
()
{
return
radiusDragCoord
})
mapControl
.
addMapItem
(
radiusDragHandle
)
radiusDragArea
=
radiusDragAreaComponent
.
createObject
(
mapControl
,
{
"
itemIndicator
"
:
radiusDragHandle
,
"
itemCoordinate
"
:
radiusDragCoord
})
centerDragHandle
=
dragHandleComponent
.
createObject
(
mapControl
)
centerDragHandle
.
coordinate
=
Qt
.
binding
(
function
()
{
return
circleCenterCoord
})
mapControl
.
addMapItem
(
centerDragHandle
)
centerDragArea
=
centerDragAreaComponent
.
createObject
(
mapControl
,
{
"
itemIndicator
"
:
centerDragHandle
,
"
itemCoordinate
"
:
circleCenterCoord
})
}
Component.onDestruction
:
{
dragHandle
.
destroy
()
dragArea
.
destroy
()
centerDragHandle
.
destroy
()
centerDragArea
.
destroy
()
radiusDragHandle
.
destroy
()
radiusDragArea
.
destroy
()
}
}
}
...
...
src/MissionManager/StructureScanComplexItem.cc
View file @
e163d336
...
...
@@ -63,9 +63,11 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie
connect
(
&
_altitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_updateCoordinateAltitudes
);
connect
(
&
_structurePolygon
,
&
QGCMapPolygon
::
dirtyChanged
,
this
,
&
StructureScanComplexItem
::
_polygonDirtyChanged
);
connect
(
&
_structurePolygon
,
&
QGCMapPolygon
::
countChanged
,
this
,
&
StructureScanComplexItem
::
_polygonCountChanged
);
connect
(
&
_structurePolygon
,
&
QGCMapPolygon
::
pathChanged
,
this
,
&
StructureScanComplexItem
::
_rebuildFlightPolygon
);
connect
(
&
_structurePolygon
,
&
QGCMapPolygon
::
countChanged
,
this
,
&
StructureScanComplexItem
::
_updateLastSequenceNumber
);
connect
(
&
_layersFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_updateLastSequenceNumber
);
connect
(
&
_flightPolygon
,
&
QGCMapPolygon
::
pathChanged
,
this
,
&
StructureScanComplexItem
::
_flightPathChanged
);
connect
(
_cameraCalc
.
distanceToSurface
(),
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_rebuildFlightPolygon
);
...
...
@@ -108,19 +110,23 @@ void StructureScanComplexItem::_clearInternal(void)
emit
lastSequenceNumberChanged
(
lastSequenceNumber
());
}
void
StructureScanComplexItem
::
_
polygonCountChanged
(
int
count
)
void
StructureScanComplexItem
::
_
updateLastSequenceNumber
(
void
)
{
Q_UNUSED
(
count
);
emit
lastSequenceNumberChanged
(
lastSequenceNumber
());
}
int
StructureScanComplexItem
::
lastSequenceNumber
(
void
)
const
{
return
_sequenceNumber
+
(
_layersFact
.
rawValue
().
toInt
()
*
((
_flightPolygon
.
count
()
+
1
)
+
// 1 waypoint for each polygon vertex + 1 to go back to first polygon vertex for each layer
2
))
+
// Camera trigger start/stop for each layer
2
;
// ROI_WPNEXT_OFFSET and ROI_NONE commands
// Each structure layer contains:
// 1 waypoint for each polygon vertex + 1 to go back to first polygon vertex for each layer
// Two commands for camera trigger start/stop
int
layerItemCount
=
_flightPolygon
.
count
()
+
1
+
2
;
int
multiLayerItemCount
=
layerItemCount
*
_layersFact
.
rawValue
().
toInt
();
int
itemCount
=
multiLayerItemCount
+
2
;
// +2 for ROI_WPNEXT_OFFSET and ROI_NONE commands
return
_sequenceNumber
+
itemCount
-
1
;
}
void
StructureScanComplexItem
::
setDirty
(
bool
dirty
)
...
...
src/MissionManager/StructureScanComplexItem.h
View file @
e163d336
...
...
@@ -107,13 +107,13 @@ signals:
private
slots
:
void
_setDirty
(
void
);
void
_polygonDirtyChanged
(
bool
dirty
);
void
_polygonCountChanged
(
int
count
);
void
_flightPathChanged
(
void
);
void
_clearInternal
(
void
);
void
_updateCoordinateAltitudes
(
void
);
void
_rebuildFlightPolygon
(
void
);
void
_recalcCameraShots
(
void
);
void
_recalcLayerInfo
(
void
);
void
_updateLastSequenceNumber
(
void
);
private:
void
_setExitCoordinate
(
const
QGeoCoordinate
&
coordinate
);
...
...
src/MissionManager/StructureScanComplexItemTest.cc
View file @
e163d336
...
...
@@ -134,6 +134,6 @@ void StructureScanComplexItemTest::_testItemCount(void)
_initItem
();
_structureScanItem
->
appendMissionItems
(
items
,
this
);
QCOMPARE
(
items
.
count
(),
_structureScanItem
->
lastSequenceNumber
());
QCOMPARE
(
items
.
count
()
-
1
,
_structureScanItem
->
lastSequenceNumber
());
}
src/PlanView/MissionItemStatus.qml
View file @
e163d336
...
...
@@ -73,6 +73,7 @@ Rectangle {
visible
:
display
property
real
availableHeight
:
height
-
indicator
.
height
property
bool
_coordValid
:
object
.
coordinate
.
isValid
property
bool
_terrainAvailable
:
!
isNaN
(
object
.
terrainPercent
)
property
real
_terrainPercent
:
_terrainAvailable
?
object
.
terrainPercent
:
1
...
...
@@ -85,6 +86,7 @@ Rectangle {
width
:
indicator
.
width
height
:
_terrainAvailable
?
Math
.
max
(
availableHeight
*
_terrainPercent
,
1
)
:
parent
.
height
color
:
_terrainAvailable
?
(
_terrainPercent
>
object
.
altPercent
?
"
red
"
:
qgcPal
.
text
)
:
"
yellow
"
visible
:
_coordValid
}
MissionItemIndexLabel
{
...
...
src/QGCApplication.cc
View file @
e163d336
...
...
@@ -76,6 +76,7 @@
#include "FollowMe.h"
#include "MissionCommandTree.h"
#include "QGCMapPolygon.h"
#include "QGCMapCircle.h"
#include "ParameterManager.h"
#include "SettingsManager.h"
#include "QGCCorePlugin.h"
...
...
@@ -389,6 +390,7 @@ void QGCApplication::_initCommon(void)
qmlRegisterType
<
LogDownloadController
>
(
"QGroundControl.Controllers"
,
1
,
0
,
"LogDownloadController"
);
qmlRegisterType
<
SyslinkComponentController
>
(
"QGroundControl.Controllers"
,
1
,
0
,
"SyslinkComponentController"
);
qmlRegisterType
<
EditPositionDialogController
>
(
"QGroundControl.Controllers"
,
1
,
0
,
"EditPositionDialogController"
);
qmlRegisterType
<
QGCMapCircle
>
(
"QGroundControl.FlightMap"
,
1
,
0
,
"QGCMapCircle"
);
#ifndef __mobile__
qmlRegisterType
<
ViewWidgetController
>
(
"QGroundControl.Controllers"
,
1
,
0
,
"ViewWidgetController"
);
qmlRegisterType
<
CustomCommandWidgetController
>
(
"QGroundControl.Controllers"
,
1
,
0
,
"CustomCommandWidgetController"
);
...
...
src/QmlControls/DropPanel.qml
View file @
e163d336
...
...
@@ -162,8 +162,6 @@ Item {
Loader
{
id
:
panelLoader
x
:
_dropMargin
y
:
_dropMargin
onHeightChanged
:
_calcPositions
()
onWidthChanged
:
_calcPositions
()
...
...
src/QmlControls/MissionItemIndexLabel.qml
View file @
e163d336
...
...
@@ -109,7 +109,7 @@ Canvas {
verticalAlignment
:
Text
.
AlignVCenter
color
:
"
white
"
font.pointSize
:
ScreenTools
.
defaultFontPointSize
fontSizeMode
:
Text
.
Horizontal
Fit
fontSizeMode
:
Text
.
Fit
text
:
_index
}
}
...
...
src/Vehicle/Vehicle.cc
View file @
e163d336
...
...
@@ -1062,6 +1062,7 @@ void Vehicle::_setCapabilities(uint64_t capabilityBits)
qCDebug
(
VehicleLog
)
<<
QString
(
"Vehicle %1 Mavlink 2.0"
).
arg
(
_capabilityBits
&
MAV_PROTOCOL_CAPABILITY_MAVLINK2
?
supports
:
doesNotSupport
);
qCDebug
(
VehicleLog
)
<<
QString
(
"Vehicle %1 MISSION_ITEM_INT"
).
arg
(
_capabilityBits
&
MAV_PROTOCOL_CAPABILITY_MISSION_INT
?
supports
:
doesNotSupport
);
qCDebug
(
VehicleLog
)
<<
QString
(
"Vehicle %1 MISSION_COMMAND_INT"
).
arg
(
_capabilityBits
&
MAV_PROTOCOL_CAPABILITY_COMMAND_INT
?
supports
:
doesNotSupport
);
qCDebug
(
VehicleLog
)
<<
QString
(
"Vehicle %1 GeoFence"
).
arg
(
_capabilityBits
&
MAV_PROTOCOL_CAPABILITY_MISSION_FENCE
?
supports
:
doesNotSupport
);
qCDebug
(
VehicleLog
)
<<
QString
(
"Vehicle %1 RallyPoints"
).
arg
(
_capabilityBits
&
MAV_PROTOCOL_CAPABILITY_MISSION_RALLY
?
supports
:
doesNotSupport
);
}
...
...
@@ -2751,13 +2752,42 @@ void Vehicle::guidedModeChangeAltitude(double altitudeChange)
_firmwarePlugin
->
guidedModeChangeAltitude
(
this
,
altitudeChange
);
}
void
Vehicle
::
guidedModeOrbit
(
const
QGeoCoordinate
&
centerCoord
,
double
radius
,
double
velocity
,
double
a
ltitude
)
void
Vehicle
::
guidedModeOrbit
(
const
QGeoCoordinate
&
centerCoord
,
double
radius
,
double
amslA
ltitude
)
{
if
(
!
orbitModeSupported
())
{
qgcApp
()
->
showMessage
(
QStringLiteral
(
"Orbit mode not supported by Vehicle."
));
return
;
}
_firmwarePlugin
->
guidedModeOrbit
(
this
,
centerCoord
,
radius
,
velocity
,
altitude
);
double
lat
,
lon
,
alt
;
if
(
centerCoord
.
isValid
())
{
lat
=
lon
=
alt
=
qQNaN
();
}
else
{
lat
=
centerCoord
.
latitude
();
lon
=
centerCoord
.
longitude
();
alt
=
amslAltitude
;
}
if
(
capabilityBits
()
&&
MAV_PROTOCOL_CAPABILITY_COMMAND_INT
)
{
sendMavCommandInt
(
defaultComponentId
(),
MAV_CMD_DO_ORBIT
,
MAV_FRAME_GLOBAL
,
true
,
// show error if fails
radius
,
qQNaN
(),
// Use default velocity
0
,
// Vehicle points to center
qQNaN
(),
// reserved
lat
,
lon
,
alt
);
}
else
{
sendMavCommand
(
defaultComponentId
(),
MAV_CMD_DO_ORBIT
,
true
,
// show error if fails
radius
,
qQNaN
(),
// Use default velocity
0
,
// Vehicle points to center
qQNaN
(),
// reserved
lat
,
lon
,
alt
);
}
}
void
Vehicle
::
pauseVehicle
(
void
)
...
...
@@ -2816,8 +2846,34 @@ void Vehicle::sendMavCommand(int component, MAV_CMD command, bool showError, flo
{
MavCommandQueueEntry_t
entry
;
entry
.
commandInt
=
false
;
entry
.
component
=
component
;
entry
.
command
=
command
;
entry
.
showError
=
showError
;
entry
.
rgParam
[
0
]
=
param1
;
entry
.
rgParam
[
1
]
=
param2
;
entry
.
rgParam
[
2
]
=
param3
;
entry
.
rgParam
[
3
]
=
param4
;
entry
.
rgParam
[
4
]
=
param5
;
entry
.
rgParam
[
5
]
=
param6
;
entry
.
rgParam
[
6
]
=
param7
;
_mavCommandQueue
.
append
(
entry
);
if
(
_mavCommandQueue
.
count
()
==
1
)
{
_mavCommandRetryCount
=
0
;
_sendMavCommandAgain
();
}
}
void
Vehicle
::
sendMavCommandInt
(
int
component
,
MAV_CMD
command
,
MAV_FRAME
frame
,
bool
showError
,
float
param1
,
float
param2
,
float
param3
,
float
param4
,
double
param5
,
double
param6
,
float
param7
)
{
MavCommandQueueEntry_t
entry
;
entry
.
commandInt
=
true
;
entry
.
component
=
component
;
entry
.
command
=
command
;
entry
.
frame
=
frame
;
entry
.
showError
=
showError
;
entry
.
rgParam
[
0
]
=
param1
;
entry
.
rgParam
[
1
]
=
param2
;
...
...
@@ -2901,25 +2957,48 @@ void Vehicle::_sendMavCommandAgain(void)
_mavCommandAckTimer
.
start
();
mavlink_message_t
msg
;
mavlink_command_long_t
cmd
;
memset
(
&
cmd
,
0
,
sizeof
(
cmd
));
cmd
.
command
=
queuedCommand
.
command
;
cmd
.
confirmation
=
0
;
cmd
.
param1
=
queuedCommand
.
rgParam
[
0
];
cmd
.
param2
=
queuedCommand
.
rgParam
[
1
];
cmd
.
param3
=
queuedCommand
.
rgParam
[
2
];
cmd
.
param4
=
queuedCommand
.
rgParam
[
3
];
cmd
.
param5
=
queuedCommand
.
rgParam
[
4
];
cmd
.
param6
=
queuedCommand
.
rgParam
[
5
];
cmd
.
param7
=
queuedCommand
.
rgParam
[
6
];
cmd
.
target_system
=
_id
;
cmd
.
target_component
=
queuedCommand
.
component
;
mavlink_msg_command_long_encode_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
if
(
queuedCommand
.
commandInt
)
{
mavlink_command_int_t
cmd
;
memset
(
&
cmd
,
0
,
sizeof
(
cmd
));
cmd
.
target_system
=
_id
;
cmd
.
target_component
=
queuedCommand
.
component
;
cmd
.
command
=
queuedCommand
.
command
;
cmd
.
frame
=
queuedCommand
.
frame
;
cmd
.
param1
=
queuedCommand
.
rgParam
[
0
];
cmd
.
param2
=
queuedCommand
.
rgParam
[
1
];
cmd
.
param3
=
queuedCommand
.
rgParam
[
2
];
cmd
.
param4
=
queuedCommand
.
rgParam
[
3
];
cmd
.
x
=
queuedCommand
.
rgParam
[
4
]
*
qPow
(
10.0
,
7.0
);
cmd
.
y
=
queuedCommand
.
rgParam
[
5
]
*
qPow
(
10.0
,
7.0
);
cmd
.
z
=
queuedCommand
.
rgParam
[
6
];
mavlink_msg_command_int_encode_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
}
else
{
mavlink_message_t
msg
;
mavlink_command_long_t
cmd
;
memset
(
&
cmd
,
0
,
sizeof
(
cmd
));
cmd
.
target_system
=
_id
;
cmd
.
target_component
=
queuedCommand
.
component
;
cmd
.
command
=
queuedCommand
.
command
;
cmd
.
confirmation
=
0
;
cmd
.
param1
=
queuedCommand
.
rgParam
[
0
];
cmd
.
param2
=
queuedCommand
.
rgParam
[
1
];
cmd
.
param3
=
queuedCommand
.
rgParam
[
2
];
cmd
.
param4
=
queuedCommand
.
rgParam
[
3
];
cmd
.
param5
=
queuedCommand
.
rgParam
[
4
];
cmd
.
param6
=
queuedCommand
.
rgParam
[
5
];
cmd
.
param7
=
queuedCommand
.
rgParam
[
6
];
mavlink_msg_command_long_encode_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
}
sendMessageOnLink
(
priorityLink
(),
msg
);
}
...
...
src/Vehicle/Vehicle.h
View file @
e163d336
...
...
@@ -582,11 +582,10 @@ public:
Q_INVOKABLE
void
guidedModeChangeAltitude
(
double
altitudeChange
);
/// Command vehicle to orbit given center point
/// @param centerCoord
Center Coordinates
/// @param centerCoord
Orit around this point
/// @param radius Distance from vehicle to centerCoord
/// @param velocity Orbit velocity (positive CW, negative CCW)
/// @param altitude Desired Vehicle Altitude
Q_INVOKABLE
void
guidedModeOrbit
(
const
QGeoCoordinate
&
centerCoord
=
QGeoCoordinate
(),
double
radius
=
NAN
,
double
velocity
=
NAN
,
double
altitude
=
NAN
);
/// @param amslAltitude Desired vehicle altitude
Q_INVOKABLE
void
guidedModeOrbit
(
const
QGeoCoordinate
&
centerCoord
,
double
radius
,
double
amslAltitude
);
/// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
/// in guided mode after pause.
...
...
@@ -841,6 +840,7 @@ public:
/// @param showError true: Display error to user if command failed, false: no error shown
/// Signals: mavCommandResult on success or failure
void
sendMavCommand
(
int
component
,
MAV_CMD
command
,
bool
showError
,
float
param1
=
0
.
0
f
,
float
param2
=
0
.
0
f
,
float
param3
=
0
.
0
f
,
float
param4
=
0
.
0
f
,
float
param5
=
0
.
0
f
,
float
param6
=
0
.
0
f
,
float
param7
=
0
.
0
f
);
void
sendMavCommandInt
(
int
component
,
MAV_CMD
command
,
MAV_FRAME
frame
,
bool
showError
,
float
param1
,
float
param2
,
float
param3
,
float
param4
,
double
param5
,
double
param6
,
float
param7
);
/// Same as sendMavCommand but available from Qml.
Q_INVOKABLE
void
sendCommand
(
int
component
,
int
command
,
bool
showError
,
double
param1
=
0
.
0
f
,
double
param2
=
0
.
0
f
,
double
param3
=
0
.
0
f
,
double
param4
=
0
.
0
f
,
double
param5
=
0
.
0
f
,
double
param6
=
0
.
0
f
,
double
param7
=
0
.
0
f
)
...
...
@@ -1180,10 +1180,12 @@ private:
QGCCameraManager
*
_cameras
;
typedef
struct
{
int
component
;
MAV_CMD
command
;
float
rgParam
[
7
];
bool
showError
;
int
component
;
bool
commandInt
;
// true: use COMMAND_INT, false: use COMMAND_LONG
MAV_CMD
command
;
MAV_FRAME
frame
;
double
rgParam
[
7
];
bool
showError
;
}
MavCommandQueueEntry_t
;
QList
<
MavCommandQueueEntry_t
>
_mavCommandQueue
;
...
...
src/comm/QGCXPlaneLink.cc
View file @
e163d336
...
...
@@ -532,6 +532,10 @@ void QGCXPlaneLink::updateActuatorControls(quint64 time, quint64 flags, float ct
p
.
f
[
6
]
=
ctl_3
;
p
.
f
[
7
]
=
ctl_3
;
writeBytesSafe
((
const
char
*
)
&
p
,
sizeof
(
p
));
/* Send flap signals, assuming that they are mapped to channel 5 (ctl_4) */
sendDataRef
(
"sim/flightmodel/controls/flaprqst"
,
ctl_4
);
sendDataRef
(
"sim/flightmodel/controls/flap2rqst"
,
ctl_4
);
break
;
}
...
...
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