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
cec81a75
Commit
cec81a75
authored
Sep 13, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Rework guided takeoff to be a capability bit
parent
47a9895a
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
44 additions
and
37 deletions
+44
-37
FirmwarePlugin.cc
src/FirmwarePlugin/FirmwarePlugin.cc
+16
-0
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+4
-0
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+5
-4
GuidedActionsController.qml
src/FlightDisplay/GuidedActionsController.qml
+1
-1
Vehicle.cc
src/Vehicle/Vehicle.cc
+6
-12
Vehicle.h
src/Vehicle/Vehicle.h
+12
-20
No files found.
src/FirmwarePlugin/FirmwarePlugin.cc
View file @
cec81a75
...
...
@@ -530,3 +530,19 @@ bool FirmwarePlugin::hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitc
yawSupported
=
false
;
return
false
;
}
bool
FirmwarePlugin
::
isVtol
(
const
Vehicle
*
vehicle
)
const
{
switch
(
vehicle
->
vehicleType
())
{
case
MAV_TYPE_VTOL_DUOROTOR
:
case
MAV_TYPE_VTOL_QUADROTOR
:
case
MAV_TYPE_VTOL_TILTROTOR
:
case
MAV_TYPE_VTOL_RESERVED2
:
case
MAV_TYPE_VTOL_RESERVED3
:
case
MAV_TYPE_VTOL_RESERVED4
:
case
MAV_TYPE_VTOL_RESERVED5
:
return
true
;
default:
return
false
;
}
}
src/FirmwarePlugin/FirmwarePlugin.h
View file @
cec81a75
...
...
@@ -45,6 +45,7 @@ public:
PauseVehicleCapability
=
1
<<
2
,
///< Vehicle supports pausing at current location
GuidedModeCapability
=
1
<<
3
,
///< Vehicle supports guided mode commands
OrbitModeCapability
=
1
<<
4
,
///< Vehicle supports orbit mode
TakeoffVehicleCapability
=
1
<<
5
,
///< Vehicle supports guided takeoff
}
FirmwareCapabilities
;
/// Maps from on parameter name to another
...
...
@@ -286,6 +287,9 @@ public:
/// @return true: vehicle has gimbal, false: gimbal support unknown
virtual
bool
hasGimbal
(
Vehicle
*
vehicle
,
bool
&
rollSupported
,
bool
&
pitchSupported
,
bool
&
yawSupported
);
/// Returns true if the vehicle is a VTOL
virtual
bool
isVtol
(
const
Vehicle
*
vehicle
)
const
;
// FIXME: Hack workaround for non pluginize FollowMe support
static
const
char
*
px4FollowMeFlightMode
;
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
cec81a75
...
...
@@ -227,11 +227,12 @@ bool PX4FirmwarePlugin::supportsManualControl(void)
bool
PX4FirmwarePlugin
::
isCapable
(
const
Vehicle
*
vehicle
,
FirmwareCapabilities
capabilities
)
{
if
(
vehicle
->
multiRotor
())
{
return
(
capabilities
&
(
MavCmdPreflightStorageCapability
|
GuidedModeCapability
|
SetFlightModeCapability
|
PauseVehicleCapability
/*| OrbitModeCapability still NYI*/
))
==
capabilities
;
}
else
{
return
(
capabilities
&
(
MavCmdPreflightStorageCapability
|
GuidedModeCapability
|
SetFlightModeCapability
|
PauseVehicleCapability
))
==
capabilities
;
int
available
=
MavCmdPreflightStorageCapability
|
SetFlightModeCapability
|
PauseVehicleCapability
|
GuidedModeCapability
;
if
(
vehicle
->
multiRotor
()
||
vehicle
->
vtol
())
{
available
|=
TakeoffVehicleCapability
;
}
return
(
capabilities
&
available
)
==
capabilities
;
}
void
PX4FirmwarePlugin
::
initializeVehicle
(
Vehicle
*
vehicle
)
...
...
src/FlightDisplay/GuidedActionsController.qml
View file @
cec81a75
...
...
@@ -92,7 +92,7 @@ Item {
property
bool
showArm
:
_activeVehicle
&&
!
_vehicleArmed
property
bool
showDisarm
:
_activeVehicle
&&
_vehicleArmed
&&
!
_vehicleFlying
property
bool
showRTL
:
_activeVehicle
&&
_vehicleArmed
&&
_activeVehicle
.
guidedModeSupported
&&
_vehicleFlying
&&
!
_vehicleInRTLMode
property
bool
showTakeoff
:
_activeVehicle
&&
_activeVehicle
.
guidedModeSupported
&&
!
_vehicleFlying
&&
!
_activeVehicle
.
fixedW
ing
property
bool
showTakeoff
:
_activeVehicle
&&
_activeVehicle
.
takeoffVehicleSupported
&&
!
_vehicleFly
ing
property
bool
showLand
:
_activeVehicle
&&
_activeVehicle
.
guidedModeSupported
&&
_vehicleArmed
&&
!
_activeVehicle
.
fixedWing
&&
!
_vehicleInLandMode
property
bool
showStartMission
:
_activeVehicle
&&
_missionAvailable
&&
!
_missionActive
&&
!
_vehicleFlying
property
bool
showContinueMission
:
_activeVehicle
&&
_missionAvailable
&&
!
_missionActive
&&
_vehicleFlying
&&
(
_currentMissionIndex
<
missionController
.
visualItems
.
count
-
1
)
...
...
src/Vehicle/Vehicle.cc
View file @
cec81a75
...
...
@@ -2094,18 +2094,7 @@ bool Vehicle::multiRotor(void) const
bool
Vehicle
::
vtol
(
void
)
const
{
switch
(
vehicleType
())
{
case
MAV_TYPE_VTOL_DUOROTOR
:
case
MAV_TYPE_VTOL_QUADROTOR
:
case
MAV_TYPE_VTOL_TILTROTOR
:
case
MAV_TYPE_VTOL_RESERVED2
:
case
MAV_TYPE_VTOL_RESERVED3
:
case
MAV_TYPE_VTOL_RESERVED4
:
case
MAV_TYPE_VTOL_RESERVED5
:
return
true
;
default:
return
false
;
}
return
_firmwarePlugin
->
isVtol
(
this
);
}
bool
Vehicle
::
supportsManualControl
(
void
)
const
...
...
@@ -2224,6 +2213,11 @@ bool Vehicle::orbitModeSupported() const
return
_firmwarePlugin
->
isCapable
(
this
,
FirmwarePlugin
::
OrbitModeCapability
);
}
bool
Vehicle
::
takeoffVehicleSupported
()
const
{
return
_firmwarePlugin
->
isCapable
(
this
,
FirmwarePlugin
::
TakeoffVehicleCapability
);
}
void
Vehicle
::
guidedModeRTL
(
void
)
{
if
(
!
guidedModeSupported
())
{
...
...
src/Vehicle/Vehicle.h
View file @
cec81a75
...
...
@@ -319,23 +319,14 @@ public:
Q_PROPERTY
(
QmlObjectListModel
*
adsbVehicles
READ
adsbVehicles
CONSTANT
)
Q_PROPERTY
(
bool
initialPlanRequestComplete
READ
initialPlanRequestComplete
NOTIFY
initialPlanRequestCompleteChanged
)
/// true: Vehicle is flying, false: Vehicle is on ground
Q_PROPERTY
(
bool
flying
READ
flying
NOTIFY
flyingChanged
)
/// true: Vehicle is flying, false: Vehicle is on ground
Q_PROPERTY
(
bool
landing
READ
landing
NOTIFY
landingChanged
)
/// true: Vehicle is in Guided mode and can respond to guided commands, false: vehicle cannot respond to direct control commands
Q_PROPERTY
(
bool
guidedMode
READ
guidedMode
WRITE
setGuidedMode
NOTIFY
guidedModeChanged
)
/// true: Guided mode commands are supported by this vehicle
Q_PROPERTY
(
bool
guidedModeSupported
READ
guidedModeSupported
CONSTANT
)
/// true: pauseVehicle command is supported
Q_PROPERTY
(
bool
pauseVehicleSupported
READ
pauseVehicleSupported
CONSTANT
)
/// true: Orbit mode is supported by this vehicle
Q_PROPERTY
(
bool
orbitModeSupported
READ
orbitModeSupported
CONSTANT
)
// Vehicle state used for guided control
Q_PROPERTY
(
bool
flying
READ
flying
NOTIFY
flyingChanged
)
///< Vehicle is flying
Q_PROPERTY
(
bool
landing
READ
landing
NOTIFY
landingChanged
)
///< Vehicle is in landing pattern (DO_LAND_START)
Q_PROPERTY
(
bool
guidedMode
READ
guidedMode
WRITE
setGuidedMode
NOTIFY
guidedModeChanged
)
///< Vehicle is in Guided mode and can respond to guided commands
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
takeoffVehicleSupported
READ
takeoffVehicleSupported
CONSTANT
)
///< Guided takeoff supported
Q_PROPERTY
(
ParameterManager
*
parameterManager
READ
parameterManager
CONSTANT
)
...
...
@@ -441,9 +432,10 @@ public:
Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs);
#endif
bool
guidedModeSupported
(
void
)
const
;
bool
pauseVehicleSupported
(
void
)
const
;
bool
orbitModeSupported
(
void
)
const
;
bool
guidedModeSupported
(
void
)
const
;
bool
pauseVehicleSupported
(
void
)
const
;
bool
orbitModeSupported
(
void
)
const
;
bool
takeoffVehicleSupported
(
void
)
const
;
// Property accessors
...
...
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