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
1f283ad0
Unverified
Commit
1f283ad0
authored
Jul 28, 2019
by
Gus Grubba
Committed by
GitHub
Jul 28, 2019
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #7632 from mavlink/tweaks
Tweaks
parents
d7ec437d
47b1050a
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
43 additions
and
24 deletions
+43
-24
QGCCameraIO.cc
src/Camera/QGCCameraIO.cc
+21
-21
VideoManager.cc
src/FlightDisplay/VideoManager.cc
+6
-0
QGCApplication.h
src/QGCApplication.h
+1
-1
ScreenToolsController.cc
src/QmlControls/ScreenToolsController.cc
+6
-0
ScreenToolsController.h
src/QmlControls/ScreenToolsController.h
+5
-2
MainRootWindow.qml
src/ui/MainRootWindow.qml
+4
-0
No files found.
src/Camera/QGCCameraIO.cc
View file @
1f283ad0
...
...
@@ -76,7 +76,7 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
break
;
default:
qWarning
()
<<
"Unsupported fact type"
<<
_fact
->
type
()
<<
"for"
<<
_fact
->
name
();
//
Fall through
//
-- Fall Through (screw clang)
case
FactMetaData
:
:
valueTypeInt32
:
_mavParamType
=
MAV_PARAM_EXT_TYPE_INT32
;
break
;
...
...
@@ -140,25 +140,25 @@ QGCCameraParamIO::_sendParameter()
switch
(
factType
)
{
case
FactMetaData
:
:
valueTypeUint8
:
case
FactMetaData
:
:
valueTypeBool
:
union_value
.
param_uint8
=
(
uint8_t
)
_fact
->
rawValue
().
toUInt
(
);
union_value
.
param_uint8
=
static_cast
<
uint8_t
>
(
_fact
->
rawValue
().
toUInt
()
);
break
;
case
FactMetaData
:
:
valueTypeInt8
:
union_value
.
param_int8
=
(
int8_t
)
_fact
->
rawValue
().
toInt
(
);
union_value
.
param_int8
=
static_cast
<
int8_t
>
(
_fact
->
rawValue
().
toInt
()
);
break
;
case
FactMetaData
:
:
valueTypeUint16
:
union_value
.
param_uint16
=
(
uint16_t
)
_fact
->
rawValue
().
toUInt
(
);
union_value
.
param_uint16
=
static_cast
<
uint16_t
>
(
_fact
->
rawValue
().
toUInt
()
);
break
;
case
FactMetaData
:
:
valueTypeInt16
:
union_value
.
param_int16
=
(
int16_t
)
_fact
->
rawValue
().
toInt
(
);
union_value
.
param_int16
=
static_cast
<
int16_t
>
(
_fact
->
rawValue
().
toInt
()
);
break
;
case
FactMetaData
:
:
valueTypeUint32
:
union_value
.
param_uint32
=
(
uint32_t
)
_fact
->
rawValue
().
toUInt
(
);
union_value
.
param_uint32
=
static_cast
<
uint32_t
>
(
_fact
->
rawValue
().
toUInt
()
);
break
;
case
FactMetaData
:
:
valueTypeInt64
:
union_value
.
param_int64
=
(
int64_t
)
_fact
->
rawValue
().
toLongLong
(
);
union_value
.
param_int64
=
static_cast
<
int64_t
>
(
_fact
->
rawValue
().
toLongLong
()
);
break
;
case
FactMetaData
:
:
valueTypeUint64
:
union_value
.
param_uint64
=
(
uint64_t
)
_fact
->
rawValue
().
toULongLong
(
);
union_value
.
param_uint64
=
static_cast
<
uint64_t
>
(
_fact
->
rawValue
().
toULongLong
()
);
break
;
case
FactMetaData
:
:
valueTypeFloat
:
union_value
.
param_float
=
_fact
->
rawValue
().
toFloat
();
...
...
@@ -171,23 +171,23 @@ QGCCameraParamIO::_sendParameter()
case
FactMetaData
:
:
valueTypeCustom
:
{
QByteArray
custom
=
_fact
->
rawValue
().
toByteArray
();
memcpy
(
union_value
.
bytes
,
custom
.
data
(),
st
d
::
max
(
custom
.
size
(),
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
));
memcpy
(
union_value
.
bytes
,
custom
.
data
(),
st
atic_cast
<
size_t
>
(
std
::
max
(
custom
.
size
(),
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
)
));
}
break
;
default:
qCritical
()
<<
"Unsupported fact type"
<<
factType
<<
"for"
<<
_fact
->
name
();
//
fall through
//
-- Fall Through (screw clang)
case
FactMetaData
:
:
valueTypeInt32
:
union_value
.
param_int32
=
(
int32_t
)
_fact
->
rawValue
().
toInt
(
);
union_value
.
param_int32
=
static_cast
<
int32_t
>
(
_fact
->
rawValue
().
toInt
()
);
break
;
}
memcpy
(
&
p
.
param_value
[
0
],
&
union_value
.
bytes
[
0
],
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
);
p
.
target_system
=
(
uint8_t
)
_vehicle
->
id
(
);
p
.
target_component
=
(
uint8_t
)
_control
->
compID
(
);
p
.
target_system
=
static_cast
<
uint8_t
>
(
_vehicle
->
id
()
);
p
.
target_component
=
static_cast
<
uint8_t
>
(
_control
->
compID
()
);
strncpy
(
p
.
param_id
,
_fact
->
name
().
toStdString
().
c_str
(),
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_ID_LEN
);
mavlink_msg_param_ext_set_encode_chan
(
_pMavlink
->
getSystemId
(
),
_pMavlink
->
getComponentId
(
),
static_cast
<
uint8_t
>
(
_pMavlink
->
getSystemId
()
),
static_cast
<
uint8_t
>
(
_pMavlink
->
getComponentId
()
),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
p
);
...
...
@@ -301,10 +301,10 @@ QGCCameraParamIO::_valueFromMessage(const char* value, uint8_t param_type)
var
=
QVariant
(
u
.
param_int32
);
break
;
case
MAV_PARAM_EXT_TYPE_UINT64
:
var
=
QVariant
(
(
qulonglong
)
u
.
param_uint64
);
var
=
QVariant
(
static_cast
<
qulonglong
>
(
u
.
param_uint64
)
);
break
;
case
MAV_PARAM_EXT_TYPE_INT64
:
var
=
QVariant
(
(
qlonglong
)
u
.
param_int64
);
var
=
QVariant
(
static_cast
<
qulonglong
>
(
u
.
param_int64
)
);
break
;
case
MAV_PARAM_EXT_TYPE_CUSTOM
:
var
=
QVariant
(
QByteArray
(
value
,
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
));
...
...
@@ -356,12 +356,12 @@ QGCCameraParamIO::paramRequest(bool reset)
strncpy
(
param_id
,
_fact
->
name
().
toStdString
().
c_str
(),
MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN
);
mavlink_message_t
msg
;
mavlink_msg_param_ext_request_read_pack_chan
(
_pMavlink
->
getSystemId
(
),
_pMavlink
->
getComponentId
(
),
static_cast
<
uint8_t
>
(
_pMavlink
->
getSystemId
()
),
static_cast
<
uint8_t
>
(
_pMavlink
->
getComponentId
()
),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
_vehicle
->
id
(
),
_control
->
compID
(
),
static_cast
<
uint8_t
>
(
_vehicle
->
id
()
),
static_cast
<
uint8_t
>
(
_control
->
compID
()
),
param_id
,
-
1
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
...
...
src/FlightDisplay/VideoManager.cc
View file @
1f283ad0
...
...
@@ -291,14 +291,20 @@ VideoManager::_updateSettings()
qCDebug
(
VideoManagerLog
)
<<
"Configure primary stream: "
<<
pInfo
->
uri
();
switch
(
pInfo
->
type
())
{
case
VIDEO_STREAM_TYPE_RTSP
:
_videoReceiver
->
setUri
(
pInfo
->
uri
());
_toolbox
->
settingsManager
()
->
videoSettings
()
->
videoSource
()
->
setRawValue
(
VideoSettings
::
videoSourceRTSP
);
break
;
case
VIDEO_STREAM_TYPE_TCP_MPEG
:
_videoReceiver
->
setUri
(
pInfo
->
uri
());
_toolbox
->
settingsManager
()
->
videoSettings
()
->
videoSource
()
->
setRawValue
(
VideoSettings
::
videoSourceTCP
);
break
;
case
VIDEO_STREAM_TYPE_RTPUDP
:
_videoReceiver
->
setUri
(
QStringLiteral
(
"udp://0.0.0.0:%1"
).
arg
(
pInfo
->
uri
()));
_toolbox
->
settingsManager
()
->
videoSettings
()
->
videoSource
()
->
setRawValue
(
VideoSettings
::
videoSourceUDPH264
);
break
;
case
VIDEO_STREAM_TYPE_MPEG_TS_H264
:
_videoReceiver
->
setUri
(
QStringLiteral
(
"mpegts://0.0.0.0:%1"
).
arg
(
pInfo
->
uri
()));
_toolbox
->
settingsManager
()
->
videoSettings
()
->
videoSource
()
->
setRawValue
(
VideoSettings
::
videoSourceMPEGTS
);
break
;
default:
_videoReceiver
->
setUri
(
pInfo
->
uri
());
...
...
src/QGCApplication.h
View file @
1f283ad0
...
...
@@ -79,7 +79,7 @@ public:
void
showMessage
(
const
QString
&
message
);
/// @return true: Fake ui into showing mobile interface
bool
fakeMobile
(
void
)
{
return
_fakeMobile
;
}
bool
fakeMobile
(
void
)
const
{
return
_fakeMobile
;
}
// Still working on getting rid of this and using dependency injection instead for everything
QGCToolbox
*
toolbox
(
void
)
{
return
_toolbox
;
}
...
...
src/QmlControls/ScreenToolsController.cc
View file @
1f283ad0
...
...
@@ -26,6 +26,12 @@ ScreenToolsController::ScreenToolsController()
}
bool
ScreenToolsController
::
hasTouch
()
const
{
return
QTouchDevice
::
devices
().
count
()
>
0
||
isMobile
();
}
QString
ScreenToolsController
::
iOSDevice
()
const
{
...
...
src/QmlControls/ScreenToolsController.h
View file @
1f283ad0
...
...
@@ -37,6 +37,7 @@ public:
Q_PROPERTY
(
bool
isLinux
READ
isLinux
CONSTANT
)
Q_PROPERTY
(
bool
isWindows
READ
isWindows
CONSTANT
)
Q_PROPERTY
(
bool
isSerialAvailable
READ
isSerialAvailable
CONSTANT
)
Q_PROPERTY
(
bool
hasTouch
READ
hasTouch
CONSTANT
)
Q_PROPERTY
(
QString
iOSDevice
READ
iOSDevice
CONSTANT
)
Q_PROPERTY
(
QString
fixedFontFamily
READ
fixedFontFamily
CONSTANT
)
Q_PROPERTY
(
QString
normalFontFamily
READ
normalFontFamily
CONSTANT
)
...
...
@@ -47,9 +48,9 @@ public:
Q_INVOKABLE
int
mouseY
(
void
)
{
return
QCursor
::
pos
().
y
();
}
#if defined(__mobile__)
bool
isMobile
()
{
return
true
;
}
bool
isMobile
()
const
{
return
true
;
}
#else
bool
isMobile
()
{
return
qgcApp
()
->
fakeMobile
();
}
bool
isMobile
()
const
{
return
qgcApp
()
->
fakeMobile
();
}
#endif
#if defined (Q_OS_ANDROID)
...
...
@@ -102,6 +103,8 @@ public:
bool
isDebug
()
{
return
false
;
}
#endif
bool
hasTouch
()
const
;
QString
iOSDevice
()
const
;
QString
fixedFontFamily
()
const
;
QString
normalFontFamily
()
const
;
...
...
src/ui/MainRootWindow.qml
View file @
1f283ad0
...
...
@@ -147,6 +147,10 @@ ApplicationWindow {
mainWindowDialog
.
dialogTitle
=
title
mainWindowDialog
.
dialogButtons
=
buttons
mainWindowDialog
.
open
()
if
(
buttons
&
StandardButton
.
Cancel
||
buttons
&
StandardButton
.
Close
||
buttons
&
StandardButton
.
Discard
||
buttons
&
StandardButton
.
Abort
||
buttons
&
StandardButton
.
Ignore
)
{
mainWindowDialog
.
closePolicy
=
Popup
.
CloseOnEscape
|
Popup
.
CloseOnPressOutside
;
mainWindowDialog
.
interactive
=
true
;
}
}
Drawer
{
...
...
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