Browse Source

Camera Manager instance management.

Remove/comment off debug output pollution
QGC4.4
Gus Grubba 8 years ago
parent
commit
7c243a53dc
  1. 2
      src/FirmwarePlugin/FirmwarePlugin.cc
  2. 4
      src/FirmwarePlugin/FirmwarePlugin.h
  3. 12
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
  4. 3
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
  5. 8
      src/FlightDisplay/GuidedActionsController.qml
  6. 4
      src/FlightDisplay/GuidedAltitudeSlider.qml
  7. 2
      src/MissionManager/MissionManager.cc
  8. 14
      src/QmlControls/QmlObjectListModel.cc
  9. 1
      src/Vehicle/MultiVehicleManager.cc
  10. 12
      src/Vehicle/Vehicle.cc
  11. 3
      src/Vehicle/Vehicle.h
  12. 4
      src/VideoStreaming/VideoReceiver.cc
  13. 4
      src/comm/MAVLinkProtocol.cc
  14. 2
      src/ui/toolbar/GPSRTKIndicator.qml

2
src/FirmwarePlugin/FirmwarePlugin.cc

@ -526,7 +526,7 @@ bool FirmwarePlugin::hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitc @@ -526,7 +526,7 @@ bool FirmwarePlugin::hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitc
return false;
}
QGCCameraManager* FirmwarePlugin::cameraManager(Vehicle* vehicle)
QGCCameraManager* FirmwarePlugin::createCameraManager(Vehicle* vehicle)
{
Q_UNUSED(vehicle);
return NULL;

4
src/FirmwarePlugin/FirmwarePlugin.h

@ -272,8 +272,8 @@ public: @@ -272,8 +272,8 @@ public:
/// TODO: This should go into QGCCameraManager
virtual const QVariantList& cameraList(const Vehicle* vehicle);
/// Vehicle camera manager. Returns NULL if not supported.
virtual QGCCameraManager* cameraManager(Vehicle *vehicle);
/// Creates vehicle camera manager. Returns NULL if not supported.
virtual QGCCameraManager* createCameraManager(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);

12
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc

@ -35,8 +35,7 @@ PX4FirmwarePluginInstanceData::PX4FirmwarePluginInstanceData(QObject* parent) @@ -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) @@ -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 @@ -558,12 +555,9 @@ bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicl
return true;
}
QGCCameraManager* PX4FirmwarePlugin::cameraManager(Vehicle* vehicle)
QGCCameraManager* PX4FirmwarePlugin::createCameraManager(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)

3
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h

@ -69,7 +69,7 @@ public: @@ -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* cameraManager (Vehicle* vehicle) override;
QGCCameraManager* createCameraManager (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: @@ -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.

8
src/FlightDisplay/GuidedActionsController.qml

@ -151,10 +151,10 @@ Item { @@ -151,10 +151,10 @@ Item {
on_CurrentMissionIndexChanged: console.log("_currentMissionIndex", _currentMissionIndex)
on_FlightModeChanged: {
_vehiclePaused = _flightMode === _activeVehicle.pauseFlightMode
_vehicleInRTLMode = _flightMode === _activeVehicle.rtlFlightMode
_vehicleInLandMode = _flightMode === _activeVehicle.landFlightMode
_vehicleInMissionMode = _flightMode === _activeVehicle.missionFlightMode // Must be last to get correct signalling for showStartMission popups
_vehiclePaused = _activeVehicle ? _flightMode === _activeVehicle.pauseFlightMode : false
_vehicleInRTLMode = _activeVehicle ? _flightMode === _activeVehicle.rtlFlightMode : false
_vehicleInLandMode = _activeVehicle ? _flightMode === _activeVehicle.landFlightMode : false
_vehicleInMissionMode = _activeVehicle ? _flightMode === _activeVehicle.missionFlightMode : false // Must be last to get correct signalling for showStartMission popups
}
// Called when an action is about to be executed in order to confirm

4
src/FlightDisplay/GuidedAltitudeSlider.qml

@ -25,8 +25,8 @@ Rectangle { @@ -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

2
src/MissionManager/MissionManager.cc

@ -860,7 +860,7 @@ void MissionManager::_finishTransaction(bool success) @@ -860,7 +860,7 @@ void MissionManager::_finishTransaction(bool success)
_transactionInProgress = TransactionNone;
if (currentTransactionType != TransactionNone) {
_transactionInProgress = TransactionNone;
qDebug() << "inProgressChanged";
//qDebug() << "inProgressChanged";
emit inProgressChanged(false);
}

14
src/QmlControls/QmlObjectListModel.cc

@ -138,18 +138,16 @@ void QmlObjectListModel::clear(void) @@ -138,18 +138,16 @@ void QmlObjectListModel::clear(void)
QObject* QmlObjectListModel::removeAt(int i)
{
QObject* removedObject = _objectList[i];
// 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)));
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;
}

1
src/Vehicle/MultiVehicleManager.cc

@ -191,6 +191,7 @@ void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle) @@ -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) {

12
src/Vehicle/Vehicle.cc

@ -229,7 +229,7 @@ Vehicle::Vehicle(LinkInterface* link, @@ -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->createCameraManager(this);
emit dynamicCamerasChanged();
}
@ -408,6 +408,16 @@ Vehicle::~Vehicle() @@ -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());

3
src/Vehicle/Vehicle.h

@ -693,6 +693,9 @@ public: @@ -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);

4
src/VideoStreaming/VideoReceiver.cc

@ -126,7 +126,7 @@ newPadCB(GstElement* element, GstPad* pad, gpointer data) @@ -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() { @@ -463,7 +463,7 @@ VideoReceiver::_handleEOS() {
} else if(_recording && _sink->removing) {
_shutdownRecordingBranch();
} else {
qCritical() << "VideoReceiver: Unexpected EOS!";
qWarning() << "VideoReceiver: Unexpected EOS!";
_shutdownPipeline();
}
}

4
src/comm/MAVLinkProtocol.cc

@ -410,10 +410,10 @@ void MAVLinkProtocol::checkForLostLogFiles(void) @@ -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());

2
src/ui/toolbar/GPSRTKIndicator.qml

@ -105,7 +105,7 @@ Item { @@ -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
}

Loading…
Cancel
Save