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
1703a30c
Commit
1703a30c
authored
Jul 26, 2017
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
c++ ownership and memory guards
parent
d2964086
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
34 additions
and
9 deletions
+34
-9
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+21
-4
QGCCameraIO.cc
src/Camera/QGCCameraIO.cc
+7
-3
QGCCameraManager.cc
src/Camera/QGCCameraManager.cc
+2
-0
Fact.cc
src/FactSystem/Fact.cc
+1
-1
UAS.cc
src/uas/UAS.cc
+1
-1
UASInterface.h
src/uas/UASInterface.h
+2
-0
No files found.
src/Camera/QGCCameraControl.cc
View file @
1703a30c
...
...
@@ -118,6 +118,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
,
_cameraMode
(
CAM_MODE_UNDEFINED
)
,
_video_status
(
VIDEO_CAPTURE_STATUS_UNDEFINED
)
{
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
memcpy
(
&
_info
,
info
,
sizeof
(
mavlink_camera_information_t
));
connect
(
this
,
&
QGCCameraControl
::
dataReady
,
this
,
&
QGCCameraControl
::
_dataReady
);
_vendor
=
QString
((
const
char
*
)(
void
*
)
&
info
->
vendor_name
[
0
]);
...
...
@@ -533,6 +534,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
}
//-- Build metadata
FactMetaData
*
metaData
=
new
FactMetaData
(
factType
,
factName
,
this
);
QQmlEngine
::
setObjectOwnership
(
metaData
,
QQmlEngine
::
CppOwnership
);
metaData
->
setShortDescription
(
description
);
metaData
->
setLongDescription
(
description
);
//-- Options (enums)
...
...
@@ -560,6 +562,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
if
(
exclusions
.
size
())
{
qCDebug
(
CameraControlLogVerbose
)
<<
"New exclusions:"
<<
factName
<<
optValue
<<
exclusions
;
QGCCameraOptionExclusion
*
pExc
=
new
QGCCameraOptionExclusion
(
this
,
factName
,
optValue
,
exclusions
);
QQmlEngine
::
setObjectOwnership
(
pExc
,
QQmlEngine
::
CppOwnership
);
_valueExclusions
.
append
(
pExc
);
}
//-- Check for range rules
...
...
@@ -589,9 +592,11 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
}
else
{
_nameToFactMetaDataMap
[
factName
]
=
metaData
;
Fact
*
pFact
=
new
Fact
(
_compID
,
factName
,
factType
,
this
);
QQmlEngine
::
setObjectOwnership
(
pFact
,
QQmlEngine
::
CppOwnership
);
pFact
->
setMetaData
(
metaData
);
pFact
->
_containerSetRawValue
(
metaData
->
rawDefaultValue
());
QGCCameraParamIO
*
pIO
=
new
QGCCameraParamIO
(
this
,
pFact
,
_vehicle
);
QQmlEngine
::
setObjectOwnership
(
pIO
,
QQmlEngine
::
CppOwnership
);
_paramIO
[
factName
]
=
pIO
;
_addFact
(
pFact
,
factName
);
}
...
...
@@ -695,8 +700,12 @@ void
QGCCameraControl
::
_requestAllParameters
()
{
//-- Reset receive list
foreach
(
QString
pramName
,
_paramIO
.
keys
())
{
_paramIO
[
pramName
]
->
setParamRequest
();
foreach
(
QString
paramName
,
_paramIO
.
keys
())
{
if
(
_paramIO
[
paramName
])
{
_paramIO
[
paramName
]
->
setParamRequest
();
}
else
{
qCritical
()
<<
"QGCParamIO is NULL"
<<
paramName
;
}
}
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_message_t
msg
;
...
...
@@ -729,7 +738,11 @@ QGCCameraControl::handleParamAck(const mavlink_param_ext_ack_t& ack)
qCWarning
(
CameraControlLog
)
<<
"Received PARAM_EXT_ACK for unknown param:"
<<
paramName
;
return
;
}
_paramIO
[
paramName
]
->
handleParamAck
(
ack
);
if
(
_paramIO
[
paramName
])
{
_paramIO
[
paramName
]
->
handleParamAck
(
ack
);
}
else
{
qCritical
()
<<
"QGCParamIO is NULL"
<<
paramName
;
}
}
//-----------------------------------------------------------------------------
...
...
@@ -741,7 +754,11 @@ QGCCameraControl::handleParamValue(const mavlink_param_ext_value_t& value)
qCWarning
(
CameraControlLog
)
<<
"Received PARAM_EXT_VALUE for unknown param:"
<<
paramName
;
return
;
}
_paramIO
[
paramName
]
->
handleParamValue
(
value
);
if
(
_paramIO
[
paramName
])
{
_paramIO
[
paramName
]
->
handleParamValue
(
value
);
}
else
{
qCritical
()
<<
"QGCParamIO is NULL"
<<
paramName
;
}
}
//-----------------------------------------------------------------------------
...
...
src/Camera/QGCCameraIO.cc
View file @
1703a30c
...
...
@@ -21,6 +21,7 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
,
_requestRetries
(
0
)
,
_done
(
false
)
{
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
_paramWriteTimer
.
setSingleShot
(
true
);
_paramWriteTimer
.
setInterval
(
1000
);
_paramRequestTimer
.
setSingleShot
(
true
);
...
...
@@ -94,10 +95,10 @@ void
QGCCameraParamIO
::
_sendParameter
()
{
//-- TODO: We should use something other than mavlink_param_union_t for PARAM_EXT_SET
mavlink_param_ext_set_t
p
;
mavlink_param_ext_set_t
p
;
memset
(
&
p
,
0
,
sizeof
(
mavlink_param_ext_set_t
));
mavlink_param_union_t
union_value
;
mavlink_message_t
msg
;
memset
(
&
p
,
0
,
sizeof
(
mavlink_param_ext_set_t
));
FactMetaData
::
ValueType_t
factType
=
_fact
->
type
();
p
.
param_type
=
_mavParamType
;
switch
(
factType
)
{
...
...
@@ -247,6 +248,9 @@ QGCCameraParamIO::_paramRequestTimeout()
}
else
{
//-- Request it again
qCDebug
(
CameraIOLog
)
<<
"Param request retry:"
<<
_fact
->
name
();
char
param_id
[
MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN
+
1
];
memset
(
param_id
,
0
,
sizeof
(
param_id
));
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
(),
...
...
@@ -255,7 +259,7 @@ QGCCameraParamIO::_paramRequestTimeout()
&
msg
,
_vehicle
->
id
(),
_control
->
compID
(),
_fact
->
name
().
toStdString
().
c_str
()
,
param_id
,
-
1
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
_paramRequestTimer
.
start
();
...
...
src/Camera/QGCCameraManager.cc
View file @
1703a30c
...
...
@@ -16,6 +16,7 @@ QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
,
_vehicleReadyState
(
false
)
,
_currentTask
(
0
)
{
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
qCDebug
(
CameraManagerLog
)
<<
"QGCCameraManager Created"
;
connect
(
qgcApp
()
->
toolbox
()
->
multiVehicleManager
(),
&
MultiVehicleManager
::
parameterReadyVehicleAvailableChanged
,
this
,
&
QGCCameraManager
::
_vehicleReady
);
connect
(
_vehicle
,
&
Vehicle
::
mavlinkMessageReceived
,
this
,
&
QGCCameraManager
::
_mavlinkMessageReceived
);
...
...
@@ -121,6 +122,7 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
qCDebug
(
CameraManagerLog
)
<<
"_handleCameraInfo:"
<<
(
const
char
*
)(
void
*
)
&
info
.
model_name
[
0
]
<<
(
const
char
*
)(
void
*
)
&
info
.
vendor_name
[
0
];
QGCCameraControl
*
pCamera
=
_vehicle
->
firmwarePlugin
()
->
createCameraControl
(
&
info
,
_vehicle
,
message
.
compid
,
this
);
if
(
pCamera
)
{
QQmlEngine
::
setObjectOwnership
(
pCamera
,
QQmlEngine
::
CppOwnership
);
_cameras
.
append
(
pCamera
);
emit
camerasChanged
();
}
...
...
src/FactSystem/Fact.cc
View file @
1703a30c
...
...
@@ -31,7 +31,7 @@ Fact::Fact(QObject* parent)
FactMetaData
*
metaData
=
new
FactMetaData
(
_type
,
this
);
setMetaData
(
metaData
);
// Better sa
g
e than sorry on object ownership
// Better sa
f
e than sorry on object ownership
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
}
...
...
src/uas/UAS.cc
View file @
1703a30c
...
...
@@ -139,9 +139,9 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi
#ifndef __mobile__
connect
(
_vehicle
,
&
Vehicle
::
mavlinkMessageReceived
,
&
fileManager
,
&
FileManager
::
receiveMessage
);
color
=
UASInterface
::
getNextColor
();
#endif
color
=
UASInterface
::
getNextColor
();
}
/**
...
...
src/uas/UASInterface.h
View file @
1703a30c
...
...
@@ -61,6 +61,7 @@ public:
* @return The next color in the color map. The map holds 20 colors and starts from the beginning
* if the colors are exceeded.
*/
#if !defined(__mobile__)
static
QColor
getNextColor
()
{
/* Create color map */
static
QList
<
QColor
>
colors
=
QList
<
QColor
>
()
...
...
@@ -91,6 +92,7 @@ public:
nextColor
++
;
return
colors
[
nextColor
];
//return the next color
}
#endif
virtual
QMap
<
int
,
QString
>
getComponents
()
=
0
;
...
...
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