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
774fad4e
Commit
774fad4e
authored
Apr 01, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Major cleanup to Guided Bar
parent
b28e00a0
Changes
19
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
19 changed files
with
296 additions
and
274 deletions
+296
-274
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+0
-10
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+0
-2
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+11
-13
ArduCopterFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
+6
-3
ArduPlaneFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc
+0
-5
ArduPlaneFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h
+0
-1
FirmwarePlugin.cc
src/FirmwarePlugin/FirmwarePlugin.cc
+0
-22
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+18
-17
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+13
-17
PX4FirmwarePlugin.h
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
+5
-3
FlightDisplayViewWidgets.qml
src/FlightDisplay/FlightDisplayViewWidgets.qml
+162
-146
FlightMap.qml
src/FlightMap/FlightMap.qml
+1
-0
qmldir
src/FlightMap/qmldir
+0
-1
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+15
-1
QGCSlider.qml
src/QmlControls/QGCSlider.qml
+39
-23
ScreenTools.qml
src/QmlControls/ScreenTools.qml
+1
-0
SliderSwitch.qml
src/QmlControls/SliderSwitch.qml
+6
-6
Vehicle.cc
src/Vehicle/Vehicle.cc
+12
-2
Vehicle.h
src/Vehicle/Vehicle.h
+7
-2
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
774fad4e
...
...
@@ -806,13 +806,3 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
return
QString
();
}
}
QString
APMFirmwarePlugin
::
missionFlightMode
(
void
)
{
return
QStringLiteral
(
"Auto"
);
}
QString
APMFirmwarePlugin
::
rtlFlightMode
(
void
)
{
return
QStringLiteral
(
"RTL"
);
}
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
774fad4e
...
...
@@ -97,8 +97,6 @@ public:
RallyPointManager
*
newRallyPointManager
(
Vehicle
*
vehicle
)
{
return
new
APMRallyPointManager
(
vehicle
);
}
QString
brandImageIndoor
(
const
Vehicle
*
vehicle
)
const
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"/qmlimages/APM/BrandImage"
);
}
QString
brandImageOutdoor
(
const
Vehicle
*
vehicle
)
const
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"/qmlimages/APM/BrandImage"
);
}
QString
missionFlightMode
(
void
)
final
;
QString
rtlFlightMode
(
void
)
final
;
protected:
/// All access to singleton is through stack specific implementation
...
...
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
774fad4e
...
...
@@ -162,13 +162,22 @@ void ArduCopterFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QG
vehicle
->
missionManager
()
->
writeArduPilotGuidedMissionItem
(
coordWithAltitude
,
false
/* altChangeOnly */
);
}
void
ArduCopterFirmwarePlugin
::
guidedModeChangeAltitude
(
Vehicle
*
vehicle
,
double
altitude
Rel
)
void
ArduCopterFirmwarePlugin
::
guidedModeChangeAltitude
(
Vehicle
*
vehicle
,
double
altitude
Change
)
{
if
(
qIsNaN
(
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
()))
{
qgcApp
()
->
showMessage
(
QStringLiteral
(
"Unable to change altitude, vehicle altitude not known."
));
return
;
}
// Don't allow altitude to fall below 3 meters above home
double
currentAltRel
=
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
();
if
(
altitudeChange
<=
0
&&
currentAltRel
<=
3
)
{
return
;
}
if
(
currentAltRel
+
altitudeChange
<
3
)
{
altitudeChange
=
3
-
currentAltRel
;
}
mavlink_message_t
msg
;
mavlink_set_position_target_local_ned_t
cmd
;
...
...
@@ -180,7 +189,7 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
cmd
.
type_mask
=
0xFFF8
;
// Only x/y/z valid
cmd
.
x
=
0.0
f
;
cmd
.
y
=
0.0
f
;
cmd
.
z
=
-
(
altitude
Rel
-
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
()
);
cmd
.
z
=
-
(
altitude
Change
);
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_msg_set_position_target_local_ned_encode_chan
(
mavlink
->
getSystemId
(),
...
...
@@ -192,11 +201,6 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
vehicle
->
sendMessageOnLink
(
vehicle
->
priorityLink
(),
msg
);
}
bool
ArduCopterFirmwarePlugin
::
isPaused
(
const
Vehicle
*
vehicle
)
const
{
return
vehicle
->
flightMode
()
==
"Brake"
;
}
void
ArduCopterFirmwarePlugin
::
pauseVehicle
(
Vehicle
*
vehicle
)
{
vehicle
->
setFlightMode
(
"Brake"
);
...
...
@@ -228,12 +232,6 @@ QString ArduCopterFirmwarePlugin::geoFenceRadiusParam(Vehicle* vehicle)
return
QStringLiteral
(
"FENCE_RADIUS"
);
}
QString
ArduCopterFirmwarePlugin
::
takeControlFlightMode
(
void
)
{
return
QStringLiteral
(
"Stabilize"
);
}
bool
ArduCopterFirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
{
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"WP_YAW_BEHAVIOR"
)))
{
...
...
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
View file @
774fad4e
...
...
@@ -54,7 +54,6 @@ public:
// Overrides from FirmwarePlugin
bool
isCapable
(
const
Vehicle
*
vehicle
,
FirmwareCapabilities
capabilities
)
final
;
bool
isPaused
(
const
Vehicle
*
vehicle
)
const
final
;
void
setGuidedMode
(
Vehicle
*
vehicle
,
bool
guidedMode
)
final
;
void
pauseVehicle
(
Vehicle
*
vehicle
)
final
;
void
guidedModeRTL
(
Vehicle
*
vehicle
)
final
;
...
...
@@ -64,14 +63,18 @@ public:
void guidedModeTakeoff(Vehicle* vehicle) final;
#endif
void
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
final
;
void
guidedModeChangeAltitude
(
Vehicle
*
vehicle
,
double
altitude
Rel
)
final
;
void
guidedModeChangeAltitude
(
Vehicle
*
vehicle
,
double
altitude
Change
)
final
;
const
FirmwarePlugin
::
remapParamNameMajorVersionMap_t
&
paramNameRemapMajorVersionMap
(
void
)
const
final
{
return
_remapParamName
;
}
int
remapParamNameHigestMinorVersionNumber
(
int
majorVersionNumber
)
const
final
;
bool
multiRotorCoaxialMotors
(
Vehicle
*
vehicle
)
final
;
bool
multiRotorXConfig
(
Vehicle
*
vehicle
)
final
;
QString
geoFenceRadiusParam
(
Vehicle
*
vehicle
)
final
;
QString
offlineEditingParamFile
(
Vehicle
*
vehicle
)
final
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
":/FirmwarePlugin/APM/Copter.OfflineEditing.params"
);
}
QString
takeControlFlightMode
(
void
)
final
;
QString
pauseFlightMode
(
void
)
const
override
{
return
QString
(
"Brake"
);
}
QString
missionFlightMode
(
void
)
const
override
{
return
QString
(
"Auto"
);
}
QString
rtlFlightMode
(
void
)
const
override
{
return
QString
(
"RTL"
);
}
QString
landFlightMode
(
void
)
const
override
{
return
QString
(
"Land"
);
}
QString
takeControlFlightMode
(
void
)
const
override
{
return
QString
(
"Stablize"
);
}
bool
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
final
;
private:
...
...
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc
View file @
774fad4e
...
...
@@ -86,8 +86,3 @@ int ArduPlaneFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVer
// Remapping supports up to 3.8
return
majorVersionNumber
==
3
?
8
:
Vehicle
::
versionNotSetValue
;
}
QString
ArduPlaneFirmwarePlugin
::
takeControlFlightMode
(
void
)
{
return
QStringLiteral
(
"Manual"
);
}
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h
View file @
774fad4e
...
...
@@ -57,7 +57,6 @@ public:
// Overrides from FirmwarePlugin
QString
offlineEditingParamFile
(
Vehicle
*
vehicle
)
final
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
":/FirmwarePlugin/APM/Plane.OfflineEditing.params"
);
}
QString
takeControlFlightMode
(
void
)
final
;
const
FirmwarePlugin
::
remapParamNameMajorVersionMap_t
&
paramNameRemapMajorVersionMap
(
void
)
const
final
{
return
_remapParamName
;
}
int
remapParamNameHigestMinorVersionNumber
(
int
majorVersionNumber
)
const
final
;
...
...
src/FirmwarePlugin/FirmwarePlugin.cc
View file @
774fad4e
...
...
@@ -237,13 +237,6 @@ void FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode)
qgcApp
()
->
showMessage
(
guided_mode_not_supported_by_vehicle
);
}
bool
FirmwarePlugin
::
isPaused
(
const
Vehicle
*
vehicle
)
const
{
// Not supported by generic vehicle
Q_UNUSED
(
vehicle
);
return
false
;
}
void
FirmwarePlugin
::
pauseVehicle
(
Vehicle
*
vehicle
)
{
// Not supported by generic vehicle
...
...
@@ -314,21 +307,6 @@ int FirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumbe
return
0
;
}
QString
FirmwarePlugin
::
missionFlightMode
(
void
)
{
return
QString
();
}
QString
FirmwarePlugin
::
rtlFlightMode
(
void
)
{
return
QString
();
}
QString
FirmwarePlugin
::
takeControlFlightMode
(
void
)
{
return
QString
();
}
QString
FirmwarePlugin
::
vehicleImageOpaque
(
const
Vehicle
*
vehicle
)
const
{
Q_UNUSED
(
vehicle
);
...
...
src/FirmwarePlugin/FirmwarePlugin.h
View file @
774fad4e
...
...
@@ -93,15 +93,27 @@ public:
/// @param[out] custom_mode Custom mode for SET_MODE mavlink message
virtual
bool
setFlightMode
(
const
QString
&
flightMode
,
uint8_t
*
base_mode
,
uint32_t
*
custom_mode
);
/// Returns The flight mode which indicates the vehicle is paused
virtual
QString
pauseFlightMode
(
void
)
const
{
return
QString
();
}
/// Returns the flight mode for running missions
virtual
QString
missionFlightMode
(
void
)
const
{
return
QString
();
}
/// Returns the flight mode for RTL
virtual
QString
rtlFlightMode
(
void
)
const
{
return
QString
();
}
/// Returns the flight mode for Land
virtual
QString
landFlightMode
(
void
)
const
{
return
QString
();
}
/// Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
virtual
QString
takeControlFlightMode
(
void
)
const
{
return
QString
();
}
/// Returns whether the vehicle is in guided mode or not.
virtual
bool
isGuidedMode
(
const
Vehicle
*
vehicle
)
const
;
/// Set guided flight mode
virtual
void
setGuidedMode
(
Vehicle
*
vehicle
,
bool
guidedMode
);
/// Returns whether the vehicle is paused or not.
virtual
bool
isPaused
(
const
Vehicle
*
vehicle
)
const
;
/// Causes the vehicle to stop at current position. If guide mode is supported, vehicle will be let in guide mode.
/// If not, vehicle will be left in Loiter.
virtual
void
pauseVehicle
(
Vehicle
*
vehicle
);
...
...
@@ -125,20 +137,9 @@ public:
/// Command vehicle to move to specified location (altitude is included and relative)
virtual
void
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
);
/// Command vehicle to change to the specified relatice altitude
virtual
void
guidedModeChangeAltitude
(
Vehicle
*
vehicle
,
double
altitudeRel
);
/// Returns the flight mode for running missions
virtual
QString
missionFlightMode
(
void
);
/// Returns the flight mode for RTL
virtual
QString
rtlFlightMode
(
void
);
/// Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
virtual
QString
takeControlFlightMode
(
void
);
/// Command vehicle to change altitude
/// @param altitudeChange If > 0, go up by amount specified, if < 0, go down by amount specified
virtual
void
guidedModeChangeAltitude
(
Vehicle
*
vehicle
,
double
altitudeChange
);
/// FIXME: This isn't quite correct being here. All code for Joystick suvehicleTypepport is currently firmware specific
/// not just this. I'm going to try to change that. If not, this will need to be removed.
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
774fad4e
...
...
@@ -399,7 +399,7 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
vehicle
->
altitudeAMSL
()
->
rawValue
().
toFloat
());
}
void
PX4FirmwarePlugin
::
guidedModeChangeAltitude
(
Vehicle
*
vehicle
,
double
altitude
Rel
)
void
PX4FirmwarePlugin
::
guidedModeChangeAltitude
(
Vehicle
*
vehicle
,
double
altitude
Change
)
{
if
(
!
vehicle
->
homePositionAvailable
())
{
qgcApp
()
->
showMessage
(
tr
(
"Unable to change altitude, home position unknown."
));
...
...
@@ -410,6 +410,17 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
return
;
}
// Don't allow altitude to fall below 3 meters above home
double
currentAltRel
=
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
();
double
newAltRel
=
currentAltRel
;
if
(
altitudeChange
<=
0
&&
currentAltRel
<=
3
)
{
return
;
}
if
(
currentAltRel
+
altitudeChange
<
3
)
{
altitudeChange
=
3
-
currentAltRel
;
}
newAltRel
=
currentAltRel
+
altitudeChange
;
vehicle
->
sendMavCommand
(
vehicle
->
defaultComponentId
(),
MAV_CMD_DO_REPOSITION
,
true
,
// show error is fails
...
...
@@ -419,7 +430,7 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
NAN
,
NAN
,
NAN
,
vehicle
->
homePosition
().
altitude
()
+
altitude
Rel
);
vehicle
->
homePosition
().
altitude
()
+
newAlt
Rel
);
}
void
PX4FirmwarePlugin
::
startMission
(
Vehicle
*
vehicle
)
...
...
@@ -504,21 +515,6 @@ void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_messag
}
}
QString
PX4FirmwarePlugin
::
missionFlightMode
(
void
)
{
return
QString
(
_missionFlightMode
);
}
QString
PX4FirmwarePlugin
::
rtlFlightMode
(
void
)
{
return
QString
(
_rtlFlightMode
);
}
QString
PX4FirmwarePlugin
::
takeControlFlightMode
(
void
)
{
return
QString
(
_manualFlightMode
);
}
bool
PX4FirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
{
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"MIS_YAWMODE"
)))
{
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
View file @
774fad4e
...
...
@@ -37,6 +37,11 @@ public:
QString
flightMode
(
uint8_t
base_mode
,
uint32_t
custom_mode
)
const
override
;
bool
setFlightMode
(
const
QString
&
flightMode
,
uint8_t
*
base_mode
,
uint32_t
*
custom_mode
)
override
;
void
setGuidedMode
(
Vehicle
*
vehicle
,
bool
guidedMode
)
override
;
QString
pauseFlightMode
(
void
)
const
override
{
return
_holdFlightMode
;
}
QString
missionFlightMode
(
void
)
const
override
{
return
_missionFlightMode
;
}
QString
rtlFlightMode
(
void
)
const
override
{
return
_rtlFlightMode
;
}
QString
landFlightMode
(
void
)
const
override
{
return
_landingFlightMode
;
}
QString
takeControlFlightMode
(
void
)
const
override
{
return
_manualFlightMode
;
}
void
pauseVehicle
(
Vehicle
*
vehicle
)
override
;
void
guidedModeRTL
(
Vehicle
*
vehicle
)
override
;
void
guidedModeLand
(
Vehicle
*
vehicle
)
override
;
...
...
@@ -61,9 +66,6 @@ public:
QString
offlineEditingParamFile
(
Vehicle
*
vehicle
)
override
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"
);
}
QString
brandImageIndoor
(
const
Vehicle
*
vehicle
)
const
override
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"/qmlimages/PX4/BrandImage"
);
}
QString
brandImageOutdoor
(
const
Vehicle
*
vehicle
)
const
override
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"/qmlimages/PX4/BrandImage"
);
}
QString
missionFlightMode
(
void
)
override
;
QString
rtlFlightMode
(
void
)
override
;
QString
takeControlFlightMode
(
void
)
override
;
bool
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
override
;
protected:
...
...
src/FlightDisplay/FlightDisplayViewWidgets.qml
View file @
774fad4e
This diff is collapsed.
Click to expand it.
src/FlightMap/FlightMap.qml
View file @
774fad4e
...
...
@@ -54,6 +54,7 @@ Map {
function
_possiblyCenterToVehiclePosition
()
{
if
(
!
firstVehiclePositionReceived
&&
allowVehicleLocationCenter
&&
activeVehicleCoordinate
.
isValid
)
{
console
.
log
(
"
Moving to initial vehicle position
"
,
QGroundControl
.
flightMapInitialZoom
)
firstVehiclePositionReceived
=
true
center
=
activeVehicleCoordinate
zoomLevel
=
QGroundControl
.
flightMapInitialZoom
...
...
src/FlightMap/qmldir
View file @
774fad4e
...
...
@@ -17,7 +17,6 @@ QGCAttitudeHUD 1.0 QGCAttitudeHUD.qml
QGCAttitudeWidget 1.0 QGCAttitudeWidget.qml
QGCCompassWidget 1.0 QGCCompassWidget.qml
QGCPitchIndicator 1.0 QGCPitchIndicator.qml
QGCSlider 1.0 QGCSlider.qml
ValuesWidget 1.0 ValuesWidget.qml
VehicleHealthWidget 1.0 VehicleHealthWidget.qml
VibrationWidget 1.0 VibrationWidget.qml
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
774fad4e
...
...
@@ -498,7 +498,21 @@ bool SimpleMissionItem::friendlyEditAllowed(void) const
}
if
(
specifiesCoordinate
()
||
specifiesAltitudeOnly
())
{
return
_missionItem
.
frame
()
==
MAV_FRAME_GLOBAL
||
_missionItem
.
frame
()
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
;
MAV_FRAME
frame
=
_missionItem
.
frame
();
switch
(
frame
)
{
case
MAV_FRAME_GLOBAL
:
case
MAV_FRAME_GLOBAL_RELATIVE_ALT
:
#if 0
Coming soon
case MAV_FRAME_GLOBAL_INT:
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
#endif
return
true
;
break
;
default:
return
false
;
}
}
return
true
;
...
...
src/QmlControls/QGCSlider.qml
View file @
774fad4e
...
...
@@ -10,47 +10,63 @@
import
QtQuick
2.3
import
QtQuick
.
Controls
1.2
import
QtQuick
.
Controls
.
Styles
1.4
import
QtQuick
.
Controls
.
Private
1.0
import
QGroundControl
.
Palette
1.0
import
QGroundControl
.
ScreenTools
1.0
import
QtQuick
.
Controls
.
Private
1.0
Slider
{
property
var
_qgcPal
:
QGCPalette
{
colorGroupEnabled
:
enabled
}
id
:
_root
implicitHeight
:
ScreenTools
.
implicitSliderHeight
// Value indicator starts display from center instead of min value
property
bool
indicatorCentered
:
false
QGCPalette
{
id
:
qgcPal
;
colorGroupEnabled
:
enabled
}
style
:
SliderStyle
{
groove
:
Item
{
property
color
fillColor
:
"
#49d
"
anchors.verticalCenter
:
parent
.
verticalCenter
implicitWidth
:
Math
.
round
(
TextSingleton
.
implicit
Height
*
4.5
)
implicitHeight
:
Math
.
max
(
6
,
Math
.
round
(
TextSingleton
.
implicitHeight
*
0.3
)
)
implicitWidth
:
Math
.
round
(
ScreenTools
.
defaultFontPixel
Height
*
4.5
)
implicitHeight
:
Math
.
round
(
ScreenTools
.
defaultFontPixelHeight
*
0.3
)
Rectangle
{
radius
:
height
/
2
anchors.fill
:
parent
border.width
:
1
border.color
:
"
#888
"
gradient
:
Gradient
{
GradientStop
{
color
:
"
#bbb
"
;
position
:
0
}
GradientStop
{
color
:
"
#ccc
"
;
position
:
0.6
}
GradientStop
{
color
:
"
#ccc
"
;
position
:
1
}
}
radius
:
height
/
2
anchors.fill
:
parent
color
:
qgcPal
.
button
border.width
:
1
border.color
:
qgcPal
.
buttonText
}
Item
{
clip
:
true
width
:
styleData
.
handlePosition
clip
:
true
x
:
_root
.
indicatorCentered
?
indicatorCenteredIndicatorStart
:
0
width
:
_root
.
indicatorCentered
?
centerIndicatorWidth
:
styleData
.
handlePosition
height
:
parent
.
height
property
real
indicatorCenteredIndicatorStart
:
Math
.
min
(
styleData
.
handlePosition
,
parent
.
width
/
2
)
property
real
indicatorCenteredIndicatorStop
:
Math
.
max
(
styleData
.
handlePosition
,
parent
.
width
/
2
)
property
real
centerIndicatorWidth
:
indicatorCenteredIndicatorStop
-
indicatorCenteredIndicatorStart
Rectangle
{
anchors.fill
:
parent
border.color
:
Qt
.
darker
(
fillColor
,
1.2
)
radius
:
height
/
2
gradient
:
Gradient
{
GradientStop
{
color
:
Qt
.
lighter
(
fillColor
,
1.3
)
;
position
:
0
}
GradientStop
{
color
:
fillColor
;
position
:
1.4
}
}
anchors.fill
:
parent
color
:
qgcPal
.
colorBlue
border.color
:
Qt
.
darker
(
color
,
1.2
)
radius
:
height
/
2
}
}
}
handle
:
Rectangle
{
anchors.centerIn
:
parent
color
:
qgcPal
.
button
border.color
:
qgcPal
.
buttonText
border.width
:
1
implicitWidth
:
_radius
*
2
implicitHeight
:
_radius
*
2
radius
:
_radius
property
real
_radius
:
Math
.
round
(
ScreenTools
.
defaultFontPixelHeight
*
0.75
)
}
}
}
src/QmlControls/ScreenTools.qml
View file @
774fad4e
...
...
@@ -70,6 +70,7 @@ Item {
property
real
implicitTextFieldHeight
:
Math
.
round
(
defaultFontPixelHeight
*
(
isMobile
?
2.0
:
1.6
))
property
real
implicitComboBoxHeight
:
Math
.
round
(
defaultFontPixelHeight
*
(
isMobile
?
2.0
:
1.6
))
property
real
implicitComboBoxWidth
:
Math
.
round
(
defaultFontPixelWidth
*
(
isMobile
?
7.0
:
5.0
))
property
real
implicitSliderHeight
:
isMobile
?
Math
.
Max
(
defaultFontPixelHeight
,
minTouchPixels
)
:
defaultFontPixelHeight
readonly
property
string
normalFontFamily
:
"
opensans
"
readonly
property
string
demiboldFontFamily
:
"
opensans-demibold
"
...
...
src/QmlControls/SliderSwitch.qml
View file @
774fad4e
...
...
@@ -7,11 +7,11 @@ import QGroundControl.Palette 1.0
/// The SliderSwitch control implements a sliding switch control similar to the power off
/// control on an iPhone.
Rectangle
{
id
:
_root
w
idth
:
label
.
contentWidth
+
(
_diameter
*
2.5
)
+
(
_border
*
4
)
h
eight
:
Math
.
max
(
ScreenTools
.
isMobile
?
ScreenTools
.
minTouchPixels
:
0
,
label
.
height
*
2.5
)
radius
:
height
/
2
color
:
qgcPal
.
window
id
:
_root
implicitW
idth
:
label
.
contentWidth
+
(
_diameter
*
2.5
)
+
(
_border
*
4
)
implicitH
eight
:
Math
.
max
(
ScreenTools
.
isMobile
?
ScreenTools
.
minTouchPixels
:
0
,
label
.
height
*
2.5
)
radius
:
height
/
2
color
:
qgcPal
.
window
signal
accept
///< Action confirmed
signal
reject
///< Action rejected
...
...
@@ -28,7 +28,7 @@ Rectangle {
id
:
label
anchors.horizontalCenter
:
parent
.
horizontalCenter
anchors.verticalCenter
:
parent
.
verticalCenter
text
:
qsTr
(
"
Slide to %1
"
).
arg
(
confirmText
)
text
:
confirmText
}
Rectangle
{
...
...
src/Vehicle/Vehicle.cc
View file @
774fad4e
...
...
@@ -1985,13 +1985,13 @@ void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord)
_firmwarePlugin
->
guidedModeGotoLocation
(
this
,
gotoCoord
);
}
void
Vehicle
::
guidedModeChangeAltitude
(
double
altitude
Rel
)
void
Vehicle
::
guidedModeChangeAltitude
(
double
altitude
Change
)
{
if
(
!
guidedModeSupported
())
{
qgcApp
()
->
showMessage
(
guided_mode_not_supported_by_vehicle
);
return
;
}
_firmwarePlugin
->
guidedModeChangeAltitude
(
this
,
altitude
Rel
);
_firmwarePlugin
->
guidedModeChangeAltitude
(
this
,
altitude
Change
);
}
void
Vehicle
::
guidedModeOrbit
(
const
QGeoCoordinate
&
centerCoord
,
double
radius
,
double
velocity
,
double
altitude
)
...
...
@@ -2397,11 +2397,21 @@ QString Vehicle::missionFlightMode(void) const
return
_firmwarePlugin
->
missionFlightMode
();
}
QString
Vehicle
::
pauseFlightMode
(
void
)
const
{
return
_firmwarePlugin
->
pauseFlightMode
();
}
QString
Vehicle
::
rtlFlightMode
(
void
)
const
{
return
_firmwarePlugin
->
rtlFlightMode
();
}
QString
Vehicle
::
landFlightMode
(
void
)
const
{
return
_firmwarePlugin
->
landFlightMode
();
}
QString
Vehicle
::
takeControlFlightMode
(
void
)
const
{
return
_firmwarePlugin
->
takeControlFlightMode
();
...
...
src/Vehicle/Vehicle.h
View file @
774fad4e
...
...
@@ -294,7 +294,9 @@ public:
Q_PROPERTY
(
QString
brandImageOutdoor
READ
brandImageOutdoor
NOTIFY
firmwareTypeChanged
)
Q_PROPERTY
(
QStringList
unhealthySensors
READ
unhealthySensors
NOTIFY
unhealthySensorsChanged
)
Q_PROPERTY
(
QString
missionFlightMode
READ
missionFlightMode
CONSTANT
)
Q_PROPERTY
(
QString
pauseFlightMode
READ
pauseFlightMode
CONSTANT
)
Q_PROPERTY
(
QString
rtlFlightMode
READ
rtlFlightMode
CONSTANT
)
Q_PROPERTY
(
QString
landFlightMode
READ
landFlightMode
CONSTANT
)
Q_PROPERTY
(
QString
takeControlFlightMode
READ
takeControlFlightMode
CONSTANT
)
Q_PROPERTY
(
QString
firmwareTypeString
READ
firmwareTypeString
NOTIFY
firmwareTypeChanged
)
Q_PROPERTY
(
QString
vehicleTypeString
READ
vehicleTypeString
NOTIFY
vehicleTypeChanged
)
...
...
@@ -384,8 +386,9 @@ public:
/// Command vehicle to move to specified location (altitude is included and relative)
Q_INVOKABLE
void
guidedModeGotoLocation
(
const
QGeoCoordinate
&
gotoCoord
);
/// Command vehicle to change to the specified relatice altitude
Q_INVOKABLE
void
guidedModeChangeAltitude
(
double
altitudeRel
);
/// Command vehicle to change altitude
/// @param altitudeChange If > 0, go up by amount specified, if < 0, go down by amount specified
Q_INVOKABLE
void
guidedModeChangeAltitude
(
double
altitudeChange
);
/// Command vehicle to orbit given center point
/// @param centerCoord Center Coordinates
...
...
@@ -575,7 +578,9 @@ public:
QString
brandImageOutdoor
()
const
;
QStringList
unhealthySensors
()
const
;
QString
missionFlightMode
()
const
;
QString
pauseFlightMode
()
const
;
QString
rtlFlightMode
()
const
;
QString
landFlightMode
()
const
;
QString
takeControlFlightMode
()
const
;
double
defaultCruiseSpeed
()
const
{
return
_defaultCruiseSpeed
;
}
double
defaultHoverSpeed
()
const
{
return
_defaultHoverSpeed
;
}
...
...
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