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
73ea13a1
Commit
73ea13a1
authored
Dec 11, 2019
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Add ROI option
parent
11ccd415
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
117 additions
and
7 deletions
+117
-7
QGCExternalLibs.pri
QGCExternalLibs.pri
+3
-3
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+1
-0
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+4
-1
FlightDisplayViewMap.qml
src/FlightDisplay/FlightDisplayViewMap.qml
+50
-3
GuidedActionsController.qml
src/FlightDisplay/GuidedActionsController.qml
+13
-0
Vehicle.cc
src/Vehicle/Vehicle.cc
+37
-0
Vehicle.h
src/Vehicle/Vehicle.h
+6
-0
QGCOptions.h
src/api/QGCOptions.h
+3
-0
No files found.
QGCExternalLibs.pri
View file @
73ea13a1
...
...
@@ -147,9 +147,9 @@ AndroidBuild {
contains(DEFINES, QGC_ENABLE_PAIRING) {
MacBuild {
#- Pairing is generally not supported on macOS. This is here solely for development.
exists(/usr/local/Cellar/openssl/1.0.2
s
/include) {
INCLUDEPATH += /usr/local/Cellar/openssl/1.0.2
s
/include
LIBS += -L/usr/local/Cellar/openssl/1.0.2
s
/lib
exists(/usr/local/Cellar/openssl/1.0.2
t
/include) {
INCLUDEPATH += /usr/local/Cellar/openssl/1.0.2
t
/include
LIBS += -L/usr/local/Cellar/openssl/1.0.2
t
/lib
LIBS += -lcrypto -lz
} else {
# There is some circular reference settings going on between QGCExternalLibs.pri and gqgroundcontrol.pro.
...
...
src/FirmwarePlugin/FirmwarePlugin.h
View file @
73ea13a1
...
...
@@ -48,6 +48,7 @@ public:
GuidedModeCapability
=
1
<<
2
,
///< Vehicle supports guided mode commands
OrbitModeCapability
=
1
<<
3
,
///< Vehicle supports orbit mode
TakeoffVehicleCapability
=
1
<<
4
,
///< Vehicle supports guided takeoff
ROIModeCapability
=
1
<<
5
,
///< Vehicle supports ROI
}
FirmwareCapabilities
;
/// Maps from on parameter name to another
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
73ea13a1
...
...
@@ -226,10 +226,13 @@ bool PX4FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_m
bool
PX4FirmwarePlugin
::
isCapable
(
const
Vehicle
*
vehicle
,
FirmwareCapabilities
capabilities
)
{
int
available
=
SetFlightModeCapability
|
PauseVehicleCapability
|
GuidedModeCapability
;
//-- This is arbitrary until I find how to really tell if ROI is avaiable
if
(
vehicle
->
multiRotor
())
{
available
|=
ROIModeCapability
;
}
if
(
vehicle
->
multiRotor
()
||
vehicle
->
vtol
())
{
available
|=
TakeoffVehicleCapability
|
OrbitModeCapability
;
}
return
(
capabilities
&
available
)
==
capabilities
;
}
...
...
src/FlightDisplay/FlightDisplayViewMap.qml
View file @
73ea13a1
...
...
@@ -401,6 +401,46 @@ FlightMap {
}
}
// ROI Location visuals
MapQuickItem
{
id
:
roiLocationItem
visible
:
false
z
:
QGroundControl
.
zOrderMapItems
anchorPoint.x
:
sourceItem
.
anchorPointX
anchorPoint.y
:
sourceItem
.
anchorPointY
sourceItem
:
MissionItemIndexLabel
{
checked
:
true
index
:
-
1
label
:
qsTr
(
"
ROI here
"
,
"
Make this a Region Of Interest
"
)
}
Connections
{
target
:
mainWindow
onActiveVehicleChanged
:
{
if
(
!
activeVehicle
)
{
roiLocationItem
.
visible
=
false
}
}
}
function
show
(
coord
)
{
roiLocationItem
.
coordinate
=
coord
roiLocationItem
.
visible
=
true
}
function
hide
()
{
roiLocationItem
.
visible
=
false
}
function
actionConfirmed
()
{
hide
()
}
function
actionCancelled
()
{
hide
()
}
}
// Orbit telemetry visuals
QGCMapCircleVisuals
{
id
:
orbitTelemetryCircle
...
...
@@ -429,9 +469,7 @@ FlightMap {
QGCMenu
{
id
:
clickMenu
property
var
coord
QGCMenuItem
{
text
:
qsTr
(
"
Go to location
"
)
visible
:
guidedActionsController
.
showGotoLocation
...
...
@@ -442,7 +480,6 @@ FlightMap {
guidedActionsController
.
confirmAction
(
guidedActionsController
.
actionGoto
,
clickMenu
.
coord
,
gotoLocationItem
)
}
}
QGCMenuItem
{
text
:
qsTr
(
"
Orbit at location
"
)
visible
:
guidedActionsController
.
showOrbit
...
...
@@ -453,6 +490,16 @@ FlightMap {
guidedActionsController
.
confirmAction
(
guidedActionsController
.
actionOrbit
,
clickMenu
.
coord
,
orbitMapCircle
)
}
}
QGCMenuItem
{
text
:
qsTr
(
"
ROI at location
"
)
visible
:
guidedActionsController
.
showROI
onTriggered
:
{
roiLocationItem
.
show
(
clickMenu
.
coord
)
gotoLocationItem
.
hide
()
guidedActionsController
.
confirmAction
(
guidedActionsController
.
actionROI
,
clickMenu
.
coord
,
orbitMapCircle
)
}
}
}
onClicked
:
{
...
...
src/FlightDisplay/GuidedActionsController.qml
View file @
73ea13a1
...
...
@@ -51,6 +51,7 @@ Item {
readonly
property
string
setWaypointTitle
:
qsTr
(
"
Set Waypoint
"
)
readonly
property
string
gotoTitle
:
qsTr
(
"
Go To Location
"
)
readonly
property
string
vtolTransitionTitle
:
qsTr
(
"
VTOL Transition
"
)
readonly
property
string
roiTitle
:
qsTr
(
"
ROI
"
)
readonly
property
string
armMessage
:
qsTr
(
"
Arm the vehicle.
"
)
readonly
property
string
disarmMessage
:
qsTr
(
"
Disarm the vehicle
"
)
...
...
@@ -70,6 +71,7 @@ Item {
readonly
property
string
mvPauseMessage
:
qsTr
(
"
Pause all vehicles at their current position.
"
)
readonly
property
string
vtolTransitionFwdMessage
:
qsTr
(
"
Transition VTOL to fixed wing flight.
"
)
readonly
property
string
vtolTransitionMRMessage
:
qsTr
(
"
Transition VTOL to multi-rotor flight.
"
)
readonly
property
string
roiMessage
:
qsTr
(
"
Make the specified location a Region Of Interest.
"
)
readonly
property
int
actionRTL
:
1
readonly
property
int
actionLand
:
2
...
...
@@ -92,6 +94,7 @@ Item {
readonly
property
int
actionMVStartMission
:
19
readonly
property
int
actionVtolTransitionToFwdFlight
:
20
readonly
property
int
actionVtolTransitionToMRFlight
:
21
readonly
property
int
actionROI
:
22
property
bool
showEmergenyStop
:
_guidedActionsEnabled
&&
!
_hideEmergenyStop
&&
_vehicleArmed
&&
_vehicleFlying
property
bool
showArm
:
_guidedActionsEnabled
&&
!
_vehicleArmed
...
...
@@ -104,6 +107,7 @@ Item {
property
bool
showPause
:
_guidedActionsEnabled
&&
_vehicleArmed
&&
activeVehicle
.
pauseVehicleSupported
&&
_vehicleFlying
&&
!
_vehiclePaused
&&
!
_fixedWingOnApproach
property
bool
showChangeAlt
:
_guidedActionsEnabled
&&
_vehicleFlying
&&
activeVehicle
.
guidedModeSupported
&&
_vehicleArmed
&&
!
_missionActive
property
bool
showOrbit
:
_guidedActionsEnabled
&&
!
_hideOrbit
&&
_vehicleFlying
&&
activeVehicle
.
orbitModeSupported
&&
!
_missionActive
property
bool
showROI
:
_guidedActionsEnabled
&&
!
_hideROI
&&
_vehicleFlying
&&
activeVehicle
.
roiModeSupported
&&
!
_missionActive
property
bool
showLandAbort
:
_guidedActionsEnabled
&&
_vehicleFlying
&&
_fixedWingOnApproach
property
bool
showGotoLocation
:
_guidedActionsEnabled
&&
_vehicleFlying
...
...
@@ -129,6 +133,7 @@ Item {
property
int
_resumeMissionIndex
:
missionController
.
resumeMissionIndex
property
bool
_hideEmergenyStop
:
!
QGroundControl
.
corePlugin
.
options
.
guidedBarShowEmergencyStop
property
bool
_hideOrbit
:
!
QGroundControl
.
corePlugin
.
options
.
guidedBarShowOrbit
property
bool
_hideROI
:
!
QGroundControl
.
corePlugin
.
options
.
guidedBarShowOrbit
property
bool
_vehicleWasFlying
:
false
property
bool
_rcRSSIAvailable
:
activeVehicle
?
activeVehicle
.
rcRSSI
>
0
&&
activeVehicle
.
rcRSSI
<=
100
:
false
property
bool
_fixedWingOnApproach
:
activeVehicle
?
activeVehicle
.
fixedWing
&&
_vehicleLanding
:
false
...
...
@@ -342,6 +347,11 @@ Item {
confirmDialog
.
message
=
vtolTransitionMRMessage
confirmDialog
.
hideTrigger
=
true
break
case
actionROI
:
confirmDialog
.
title
=
roiTitle
confirmDialog
.
message
=
roiMessage
confirmDialog
.
hideTrigger
=
Qt
.
binding
(
function
()
{
return
!
showROI
})
break
;
default
:
console
.
warn
(
"
Unknown actionCode
"
,
actionCode
)
return
...
...
@@ -417,6 +427,9 @@ Item {
case
actionVtolTransitionToMRFlight
:
activeVehicle
.
vtolInFwdFlight
=
false
break
case
actionROI
:
activeVehicle
.
guidedModeROI
(
actionData
)
break
default
:
console
.
warn
(
qsTr
(
"
Internal error: unknown actionCode
"
),
actionCode
)
break
...
...
src/Vehicle/Vehicle.cc
View file @
73ea13a1
...
...
@@ -2989,6 +2989,11 @@ bool Vehicle::orbitModeSupported() const
return
_firmwarePlugin
->
isCapable
(
this
,
FirmwarePlugin
::
OrbitModeCapability
);
}
bool
Vehicle
::
roiModeSupported
()
const
{
return
_firmwarePlugin
->
isCapable
(
this
,
FirmwarePlugin
::
ROIModeCapability
);
}
bool
Vehicle
::
takeoffVehicleSupported
()
const
{
return
_firmwarePlugin
->
isCapable
(
this
,
FirmwarePlugin
::
TakeoffVehicleCapability
);
...
...
@@ -3094,6 +3099,38 @@ void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius,
}
}
void
Vehicle
::
guidedModeROI
(
const
QGeoCoordinate
&
centerCoord
)
{
if
(
!
roiModeSupported
())
{
qgcApp
()
->
showMessage
(
QStringLiteral
(
"ROI mode not supported by Vehicle."
));
return
;
}
if
(
capabilityBits
()
&
MAV_PROTOCOL_CAPABILITY_COMMAND_INT
)
{
sendMavCommandInt
(
defaultComponentId
(),
MAV_CMD_DO_SET_ROI_LOCATION
,
MAV_FRAME_GLOBAL
,
true
,
// show error if fails
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
centerCoord
.
latitude
(),
centerCoord
.
longitude
(),
static_cast
<
float
>
(
centerCoord
.
altitude
()));
}
else
{
sendMavCommand
(
defaultComponentId
(),
MAV_CMD_DO_SET_ROI_LOCATION
,
true
,
// show error if fails
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
centerCoord
.
latitude
()),
static_cast
<
float
>
(
centerCoord
.
longitude
()),
static_cast
<
float
>
(
centerCoord
.
altitude
()));
}
}
void
Vehicle
::
pauseVehicle
(
void
)
{
if
(
!
pauseVehicleSupported
())
{
...
...
src/Vehicle/Vehicle.h
View file @
73ea13a1
...
...
@@ -654,6 +654,7 @@ public:
Q_PROPERTY
(
bool
guidedModeSupported
READ
guidedModeSupported
CONSTANT
)
///< Guided mode commands are supported by this vehicle
Q_PROPERTY
(
bool
pauseVehicleSupported
READ
pauseVehicleSupported
CONSTANT
)
///< Pause vehicle command is supported
Q_PROPERTY
(
bool
orbitModeSupported
READ
orbitModeSupported
CONSTANT
)
///< Orbit mode is supported by this vehicle
Q_PROPERTY
(
bool
roiModeSupported
READ
roiModeSupported
CONSTANT
)
///< Orbit mode is supported by this vehicle
Q_PROPERTY
(
bool
takeoffVehicleSupported
READ
takeoffVehicleSupported
CONSTANT
)
///< Guided takeoff supported
Q_PROPERTY
(
QString
gotoFlightMode
READ
gotoFlightMode
CONSTANT
)
///< Flight mode vehicle is in while performing goto
...
...
@@ -737,6 +738,10 @@ public:
/// @param amslAltitude Desired vehicle altitude
Q_INVOKABLE
void
guidedModeOrbit
(
const
QGeoCoordinate
&
centerCoord
,
double
radius
,
double
amslAltitude
);
/// Command vehicle to keep given point as ROI
/// @param centerCoord ROI coordinates
Q_INVOKABLE
void
guidedModeROI
(
const
QGeoCoordinate
&
centerCoord
);
/// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
/// in guided mode after pause.
Q_INVOKABLE
void
pauseVehicle
(
void
);
...
...
@@ -786,6 +791,7 @@ public:
bool
guidedModeSupported
(
void
)
const
;
bool
pauseVehicleSupported
(
void
)
const
;
bool
orbitModeSupported
(
void
)
const
;
bool
roiModeSupported
(
void
)
const
;
bool
takeoffVehicleSupported
(
void
)
const
;
QString
gotoFlightMode
(
void
)
const
;
...
...
src/api/QGCOptions.h
View file @
73ea13a1
...
...
@@ -49,6 +49,7 @@ public:
Q_PROPERTY
(
QString
firmwareUpgradeSingleURL
READ
firmwareUpgradeSingleURL
CONSTANT
)
Q_PROPERTY
(
bool
guidedBarShowEmergencyStop
READ
guidedBarShowEmergencyStop
NOTIFY
guidedBarShowEmergencyStopChanged
)
Q_PROPERTY
(
bool
guidedBarShowOrbit
READ
guidedBarShowOrbit
NOTIFY
guidedBarShowOrbitChanged
)
Q_PROPERTY
(
bool
guidedBarShowROI
READ
guidedBarShowROI
NOTIFY
guidedBarShowROIChanged
)
Q_PROPERTY
(
bool
missionWaypointsOnly
READ
missionWaypointsOnly
NOTIFY
missionWaypointsOnlyChanged
)
Q_PROPERTY
(
bool
multiVehicleEnabled
READ
multiVehicleEnabled
NOTIFY
multiVehicleEnabledChanged
)
Q_PROPERTY
(
bool
showOfflineMapExport
READ
showOfflineMapExport
NOTIFY
showOfflineMapExportChanged
)
...
...
@@ -110,6 +111,7 @@ public:
virtual
bool
showFirmwareUpgrade
()
const
{
return
true
;
}
virtual
bool
guidedBarShowEmergencyStop
()
const
{
return
true
;
}
virtual
bool
guidedBarShowOrbit
()
const
{
return
true
;
}
virtual
bool
guidedBarShowROI
()
const
{
return
true
;
}
virtual
bool
missionWaypointsOnly
()
const
{
return
false
;
}
///< true: Only allow waypoints and complex items in Plan
virtual
bool
multiVehicleEnabled
()
const
{
return
true
;
}
///< false: multi vehicle support is disabled
virtual
bool
guidedActionsRequireRCRSSI
()
const
{
return
false
;
}
///< true: Guided actions will be disabled is there is no RC RSSI
...
...
@@ -147,6 +149,7 @@ signals:
void
showFirmwareUpgradeChanged
(
bool
show
);
void
guidedBarShowEmergencyStopChanged
(
bool
show
);
void
guidedBarShowOrbitChanged
(
bool
show
);
void
guidedBarShowROIChanged
(
bool
show
);
void
missionWaypointsOnlyChanged
(
bool
missionWaypointsOnly
);
void
multiVehicleEnabledChanged
(
bool
multiVehicleEnabled
);
void
showOfflineMapExportChanged
();
...
...
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