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
7c243a53
Commit
7c243a53
authored
Jul 28, 2017
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Camera Manager instance management.
Remove/comment off debug output pollution
parent
b9355226
Changes
14
Show whitespace changes
Inline
Side-by-side
Showing
14 changed files
with
40 additions
and
35 deletions
+40
-35
FirmwarePlugin.cc
src/FirmwarePlugin/FirmwarePlugin.cc
+1
-1
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+2
-2
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+3
-9
PX4FirmwarePlugin.h
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
+1
-2
GuidedActionsController.qml
src/FlightDisplay/GuidedActionsController.qml
+4
-4
GuidedAltitudeSlider.qml
src/FlightDisplay/GuidedAltitudeSlider.qml
+2
-2
MissionManager.cc
src/MissionManager/MissionManager.cc
+1
-1
QmlObjectListModel.cc
src/QmlControls/QmlObjectListModel.cc
+6
-8
MultiVehicleManager.cc
src/Vehicle/MultiVehicleManager.cc
+1
-0
Vehicle.cc
src/Vehicle/Vehicle.cc
+11
-1
Vehicle.h
src/Vehicle/Vehicle.h
+3
-0
VideoReceiver.cc
src/VideoStreaming/VideoReceiver.cc
+2
-2
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+2
-2
GPSRTKIndicator.qml
src/ui/toolbar/GPSRTKIndicator.qml
+1
-1
No files found.
src/FirmwarePlugin/FirmwarePlugin.cc
View file @
7c243a53
...
...
@@ -526,7 +526,7 @@ bool FirmwarePlugin::hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitc
return
false
;
}
QGCCameraManager
*
FirmwarePlugin
::
cameraManager
(
Vehicle
*
vehicle
)
QGCCameraManager
*
FirmwarePlugin
::
c
reateC
ameraManager
(
Vehicle
*
vehicle
)
{
Q_UNUSED
(
vehicle
);
return
NULL
;
...
...
src/FirmwarePlugin/FirmwarePlugin.h
View file @
7c243a53
...
...
@@ -272,8 +272,8 @@ public:
/// TODO: This should go into QGCCameraManager
virtual
const
QVariantList
&
cameraList
(
const
Vehicle
*
vehicle
);
///
V
ehicle camera manager. Returns NULL if not supported.
virtual
QGCCameraManager
*
cameraManager
(
Vehicle
*
vehicle
);
///
Creates v
ehicle camera manager. Returns NULL if not supported.
virtual
QGCCameraManager
*
c
reateC
ameraManager
(
Vehicle
*
vehicle
);
/// Camera control. Returns NULL if not supported.
virtual
QGCCameraControl
*
createCameraControl
(
const
mavlink_camera_information_t
*
info
,
Vehicle
*
vehicle
,
int
compID
,
QObject
*
parent
=
NULL
);
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
7c243a53
...
...
@@ -35,8 +35,7 @@ PX4FirmwarePluginInstanceData::PX4FirmwarePluginInstanceData(QObject* parent)
}
PX4FirmwarePlugin
::
PX4FirmwarePlugin
(
void
)
:
_cameraManager
(
NULL
)
,
_manualFlightMode
(
tr
(
"Manual"
))
:
_manualFlightMode
(
tr
(
"Manual"
))
,
_acroFlightMode
(
tr
(
"Acro"
))
,
_stabilizedFlightMode
(
tr
(
"Stabilized"
))
,
_rattitudeFlightMode
(
tr
(
"Rattitude"
))
...
...
@@ -129,8 +128,6 @@ PX4FirmwarePlugin::PX4FirmwarePlugin(void)
PX4FirmwarePlugin
::~
PX4FirmwarePlugin
()
{
if
(
_cameraManager
)
delete
_cameraManager
;
}
AutoPilotPlugin
*
PX4FirmwarePlugin
::
autopilotPlugin
(
Vehicle
*
vehicle
)
...
...
@@ -558,12 +555,9 @@ bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicl
return
true
;
}
QGCCameraManager
*
PX4FirmwarePlugin
::
cameraManager
(
Vehicle
*
vehicle
)
QGCCameraManager
*
PX4FirmwarePlugin
::
c
reateC
ameraManager
(
Vehicle
*
vehicle
)
{
if
(
!
_cameraManager
)
{
_cameraManager
=
new
QGCCameraManager
(
vehicle
);
}
return
_cameraManager
;
return
new
QGCCameraManager
(
vehicle
);
}
QGCCameraControl
*
PX4FirmwarePlugin
::
createCameraControl
(
const
mavlink_camera_information_t
*
info
,
Vehicle
*
vehicle
,
int
compID
,
QObject
*
parent
)
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
View file @
7c243a53
...
...
@@ -69,7 +69,7 @@ public:
QString
brandImageOutdoor
(
const
Vehicle
*
vehicle
)
const
override
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"/qmlimages/PX4/BrandImage"
);
}
bool
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
override
;
QString
autoDisarmParameter
(
Vehicle
*
vehicle
)
override
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"COM_DISARM_LAND"
);
}
QGCCameraManager
*
c
ameraManager
(
Vehicle
*
vehicle
)
override
;
QGCCameraManager
*
c
reateCameraManager
(
Vehicle
*
vehicle
)
override
;
QGCCameraControl
*
createCameraControl
(
const
mavlink_camera_information_t
*
info
,
Vehicle
*
vehicle
,
int
compID
,
QObject
*
parent
=
NULL
)
override
;
protected:
...
...
@@ -83,7 +83,6 @@ protected:
}
FlightModeInfo_t
;
QList
<
FlightModeInfo_t
>
_flightModeInfoList
;
QGCCameraManager
*
_cameraManager
;
// Use these constants to set flight modes using setFlightMode method. Don't use hardcoded string names since the
// names may change.
...
...
src/FlightDisplay/GuidedActionsController.qml
View file @
7c243a53
...
...
@@ -151,10 +151,10 @@ Item {
on_CurrentMissionIndexChanged
:
console
.
log
(
"
_currentMissionIndex
"
,
_currentMissionIndex
)
on_FlightModeChanged
:
{
_vehiclePaused
=
_
flightMode
===
_activeVehicle
.
pauseFlightMod
e
_vehicleInRTLMode
=
_
flightMode
===
_activeVehicle
.
rtlFlightMod
e
_vehicleInLandMode
=
_
flightMode
===
_activeVehicle
.
landFlightMod
e
_vehicleInMissionMode
=
_
flightMode
===
_activeVehicle
.
missionFlightMod
e
// Must be last to get correct signalling for showStartMission popups
_vehiclePaused
=
_
activeVehicle
?
_flightMode
===
_activeVehicle
.
pauseFlightMode
:
fals
e
_vehicleInRTLMode
=
_
activeVehicle
?
_flightMode
===
_activeVehicle
.
rtlFlightMode
:
fals
e
_vehicleInLandMode
=
_
activeVehicle
?
_flightMode
===
_activeVehicle
.
landFlightMode
:
fals
e
_vehicleInMissionMode
=
_
activeVehicle
?
_flightMode
===
_activeVehicle
.
missionFlightMode
:
fals
e
// Must be last to get correct signalling for showStartMission popups
}
// Called when an action is about to be executed in order to confirm
...
...
src/FlightDisplay/GuidedAltitudeSlider.qml
View file @
7c243a53
...
...
@@ -25,8 +25,8 @@ Rectangle {
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
property
real
_vehicleAltitude
:
_activeVehicle
?
_activeVehicle
.
altitudeRelative
.
rawValue
:
0
property
bool
_fixedWing
:
_activeVehicle
?
_activeVehicle
.
fixedWing
:
false
property
real
_sliderMaxAlt
:
_
fixedWing
?
_guidedSettings
.
fixedWingMaximumAltitude
.
rawValue
:
_guidedSettings
.
vehicleMaximumAltitude
.
rawValue
property
real
_sliderMinAlt
:
_
fixedWing
?
_guidedSettings
.
fixedWingMinimumAltitude
.
rawValue
:
_guidedSettings
.
vehicleMinimumAltitude
.
rawValue
property
real
_sliderMaxAlt
:
_
guidedSettings
?
(
_fixedWing
?
_guidedSettings
.
fixedWingMaximumAltitude
.
rawValue
:
_guidedSettings
.
vehicleMaximumAltitude
.
rawValue
)
:
0
property
real
_sliderMinAlt
:
_
guidedSettings
?
(
_fixedWing
?
_guidedSettings
.
fixedWingMinimumAltitude
.
rawValue
:
_guidedSettings
.
vehicleMinimumAltitude
.
rawValue
)
:
0
function
reset
()
{
altSlider
.
value
=
0
...
...
src/MissionManager/MissionManager.cc
View file @
7c243a53
...
...
@@ -860,7 +860,7 @@ void MissionManager::_finishTransaction(bool success)
_transactionInProgress
=
TransactionNone
;
if
(
currentTransactionType
!=
TransactionNone
)
{
_transactionInProgress
=
TransactionNone
;
qDebug
()
<<
"inProgressChanged"
;
//
qDebug() << "inProgressChanged";
emit
inProgressChanged
(
false
);
}
...
...
src/QmlControls/QmlObjectListModel.cc
View file @
7c243a53
...
...
@@ -138,18 +138,16 @@ void QmlObjectListModel::clear(void)
QObject
*
QmlObjectListModel
::
removeAt
(
int
i
)
{
QObject
*
removedObject
=
_objectList
[
i
];
if
(
removedObject
)
{
// Look for a dirtyChanged signal on the object
if
(
_objectList
[
i
]
->
metaObject
()
->
indexOfSignal
(
QMetaObject
::
normalizedSignature
(
"dirtyChanged(bool)"
))
!=
-
1
)
{
if
(
!
_skipDirtyFirstItem
||
i
!=
0
)
{
QObject
::
disconnect
(
_objectList
[
i
],
SIGNAL
(
dirtyChanged
(
bool
)),
this
,
SLOT
(
_childDirtyChanged
(
bool
)));
}
}
}
removeRows
(
i
,
1
);
setDirty
(
true
);
return
removedObject
;
}
...
...
src/Vehicle/MultiVehicleManager.cc
View file @
7c243a53
...
...
@@ -191,6 +191,7 @@ void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle)
emit
activeVehicleAvailableChanged
(
false
);
emit
parameterReadyVehicleAvailableChanged
(
false
);
emit
vehicleRemoved
(
vehicle
);
vehicle
->
prepareDelete
();
#if defined (__ios__) || defined(__android__)
if
(
_vehicles
.
count
()
==
0
)
{
...
...
src/Vehicle/Vehicle.cc
View file @
7c243a53
...
...
@@ -229,7 +229,7 @@ Vehicle::Vehicle(LinkInterface* link,
connect
(
&
_mapTrajectoryTimer
,
&
QTimer
::
timeout
,
this
,
&
Vehicle
::
_addNewMapTrajectoryPoint
);
// Create camera manager instance
_cameras
=
_firmwarePlugin
->
cameraManager
(
this
);
_cameras
=
_firmwarePlugin
->
c
reateC
ameraManager
(
this
);
emit
dynamicCamerasChanged
();
}
...
...
@@ -408,6 +408,16 @@ Vehicle::~Vehicle()
}
void
Vehicle
::
prepareDelete
()
{
if
(
_cameras
)
{
delete
_cameras
;
_cameras
=
NULL
;
emit
dynamicCamerasChanged
();
qApp
->
processEvents
();
}
}
void
Vehicle
::
_offlineFirmwareTypeSettingChanged
(
QVariant
value
)
{
_firmwareType
=
static_cast
<
MAV_AUTOPILOT
>
(
value
.
toInt
());
...
...
src/Vehicle/Vehicle.h
View file @
7c243a53
...
...
@@ -693,6 +693,9 @@ public:
void
_setLanding
(
bool
landing
);
void
_setHomePosition
(
QGeoCoordinate
&
homeCoord
);
/// Vehicle is about to be deleted
void
prepareDelete
();
signals:
void
allLinksInactive
(
Vehicle
*
vehicle
);
void
coordinateChanged
(
QGeoCoordinate
coordinate
);
...
...
src/VideoStreaming/VideoReceiver.cc
View file @
7c243a53
...
...
@@ -126,7 +126,7 @@ newPadCB(GstElement* element, GstPad* pad, gpointer data)
{
gchar
*
name
;
name
=
gst_pad_get_name
(
pad
);
g_print
(
"A new pad %s was created
\n
"
,
name
);
//
g_print("A new pad %s was created\n", name);
GstCaps
*
p_caps
=
gst_pad_get_pad_template_caps
(
pad
);
gchar
*
description
=
gst_caps_to_string
(
p_caps
);
qCDebug
(
VideoReceiverLog
)
<<
p_caps
<<
", "
<<
description
;
...
...
@@ -463,7 +463,7 @@ VideoReceiver::_handleEOS() {
}
else
if
(
_recording
&&
_sink
->
removing
)
{
_shutdownRecordingBranch
();
}
else
{
q
Critical
()
<<
"VideoReceiver: Unexpected EOS!"
;
q
Warning
()
<<
"VideoReceiver: Unexpected EOS!"
;
_shutdownPipeline
();
}
}
...
...
src/comm/MAVLinkProtocol.cc
View file @
7c243a53
...
...
@@ -410,10 +410,10 @@ void MAVLinkProtocol::checkForLostLogFiles(void)
QString
filter
(
QString
(
"*.%1"
).
arg
(
_logFileExtension
));
QFileInfoList
fileInfoList
=
tempDir
.
entryInfoList
(
QStringList
(
filter
),
QDir
::
Files
);
qDebug
()
<<
"Orphaned log file count"
<<
fileInfoList
.
count
();
//
qDebug() << "Orphaned log file count" << fileInfoList.count();
foreach
(
const
QFileInfo
fileInfo
,
fileInfoList
)
{
qDebug
()
<<
"Orphaned log file"
<<
fileInfo
.
filePath
();
//
qDebug() << "Orphaned log file" << fileInfo.filePath();
if
(
fileInfo
.
size
()
==
0
)
{
// Delete all zero length files
QFile
::
remove
(
fileInfo
.
filePath
());
...
...
src/ui/toolbar/GPSRTKIndicator.qml
View file @
7c243a53
...
...
@@ -105,7 +105,7 @@ Item {
anchors.left
:
gpsIcon
.
right
QGCLabel
{
anchors.horizontalCenter
:
numSatValue
.
horizontalCenter
anchors.horizontalCenter
:
parent
.
horizontalCenter
color
:
qgcPal
.
buttonText
text
:
QGroundControl
.
gpsRtk
.
numSatellites
.
value
}
...
...
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