Browse Source

CameraManager: add BatteryStatus handling

QGC4.4
olliw42 6 years ago
parent
commit
225d1d15fc
  1. 21
      src/Camera/QGCCameraControl.cc
  2. 7
      src/Camera/QGCCameraControl.h
  3. 15
      src/Camera/QGCCameraManager.cc
  4. 3
      src/Camera/QGCCameraManager.h
  5. 7
      src/FlightMap/Widgets/CameraPageWidget.qml

21
src/Camera/QGCCameraControl.cc

@ -264,6 +264,16 @@ QGCCameraControl::storageFreeStr() @@ -264,6 +264,16 @@ QGCCameraControl::storageFreeStr()
}
//-----------------------------------------------------------------------------
QString
QGCCameraControl::batteryRemainingStr()
{
if(_batteryRemaining >= 0) {
return QGCMapEngine::numberToString(static_cast<quint64>(_batteryRemaining)) + " %";
}
return "";
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::setCameraMode(CameraMode mode)
{
@ -1492,6 +1502,17 @@ QGCCameraControl::handleStorageInfo(const mavlink_storage_information_t& st) @@ -1492,6 +1502,17 @@ QGCCameraControl::handleStorageInfo(const mavlink_storage_information_t& st)
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleBatteryStatus(const mavlink_battery_status_t& bs)
{
qCDebug(CameraControlLog) << "handleBatteryStatus:" << bs.battery_remaining;
if(bs.battery_remaining >= 0 && _batteryRemaining != static_cast<int>(bs.battery_remaining)) {
_batteryRemaining = static_cast<int>(bs.battery_remaining);
emit batteryRemainingChanged();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap)
{
//-- This is a response to MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS

7
src/Camera/QGCCameraControl.h

@ -155,6 +155,8 @@ public: @@ -155,6 +155,8 @@ public:
Q_PROPERTY(quint32 storageFree READ storageFree NOTIFY storageFreeChanged)
Q_PROPERTY(QString storageFreeStr READ storageFreeStr NOTIFY storageFreeChanged)
Q_PROPERTY(quint32 storageTotal READ storageTotal NOTIFY storageTotalChanged)
Q_PROPERTY(int batteryRemaining READ batteryRemaining NOTIFY batteryRemainingChanged)
Q_PROPERTY(QString batteryRemainingStr READ batteryRemainingStr NOTIFY batteryRemainingChanged)
Q_PROPERTY(bool paramComplete READ paramComplete NOTIFY parametersReady)
Q_PROPERTY(qreal zoomLevel READ zoomLevel WRITE setZoomLevel NOTIFY zoomLevelChanged)
@ -232,6 +234,8 @@ public: @@ -232,6 +234,8 @@ public:
virtual quint32 storageFree () { return _storageFree; }
virtual QString storageFreeStr ();
virtual quint32 storageTotal () { return _storageTotal; }
virtual int batteryRemaining () { return _batteryRemaining; }
virtual QString batteryRemainingStr ();
virtual bool paramComplete () { return _paramComplete; }
virtual qreal zoomLevel () { return _zoomLevel; }
virtual qreal focusLevel () { return _focusLevel; }
@ -273,6 +277,7 @@ public: @@ -273,6 +277,7 @@ public:
virtual void handleParamAck (const mavlink_param_ext_ack_t& ack);
virtual void handleParamValue (const mavlink_param_ext_value_t& value);
virtual void handleStorageInfo (const mavlink_storage_information_t& st);
virtual void handleBatteryStatus (const mavlink_battery_status_t& bs);
virtual void handleVideoInfo (const mavlink_video_stream_information_t *vi);
virtual void handleVideoStatus (const mavlink_video_stream_status_t *vs);
@ -303,6 +308,7 @@ signals: @@ -303,6 +308,7 @@ signals:
void activeSettingsChanged ();
void storageFreeChanged ();
void storageTotalChanged ();
void batteryRemainingChanged ();
void dataReady (QByteArray data);
void parametersReady ();
void zoomLevelChanged ();
@ -373,6 +379,7 @@ protected: @@ -373,6 +379,7 @@ protected:
qreal _focusLevel = 0.0;
uint32_t _storageFree = 0;
uint32_t _storageTotal = 0;
int _batteryRemaining = -1;
QNetworkAccessManager* _netManager = nullptr;
QString _modelName;
QString _vendor;

15
src/Camera/QGCCameraManager.cc

@ -97,6 +97,9 @@ QGCCameraManager::_mavlinkMessageReceived(const mavlink_message_t& message) @@ -97,6 +97,9 @@ QGCCameraManager::_mavlinkMessageReceived(const mavlink_message_t& message)
case MAVLINK_MSG_ID_VIDEO_STREAM_STATUS:
_handleVideoStreamStatus(message);
break;
case MAVLINK_MSG_ID_BATTERY_STATUS:
_handleBatteryStatus(message);
break;
}
}
}
@ -360,6 +363,18 @@ QGCCameraManager::_handleVideoStreamStatus(const mavlink_message_t& message) @@ -360,6 +363,18 @@ QGCCameraManager::_handleVideoStreamStatus(const mavlink_message_t& message)
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleBatteryStatus(const mavlink_message_t& message)
{
QGCCameraControl* pCamera = _findCamera(message.compid);
if(pCamera) {
mavlink_battery_status_t batteryStatus;
mavlink_msg_battery_status_decode(&message, &batteryStatus);
pCamera->handleBatteryStatus(batteryStatus);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_requestCameraInfo(int compID)
{
qCDebug(CameraManagerLog) << "_requestCameraInfo(" << compID << ")";

3
src/Camera/QGCCameraManager.h

@ -35,7 +35,7 @@ public: @@ -35,7 +35,7 @@ public:
//-- Return a list of cameras provided by this vehicle
virtual QmlObjectListModel* cameras () { return &_cameras; }
//-- Camera names to show the user (for selection)
virtual QStringList cameraLabels () { return _cameraLabels; }
virtual QStringList cameraLabels () { return _cameraLabels; }
//-- Current selected camera
virtual int currentCamera () { return _currentCamera; }
virtual QGCCameraControl* currentCameraInstance();
@ -79,6 +79,7 @@ protected: @@ -79,6 +79,7 @@ protected:
virtual void _handleCaptureStatus (const mavlink_message_t& message);
virtual void _handleVideoStreamInfo (const mavlink_message_t& message);
virtual void _handleVideoStreamStatus(const mavlink_message_t& message);
virtual void _handleBatteryStatus (const mavlink_message_t& message);
protected:

7
src/FlightMap/Widgets/CameraPageWidget.qml

@ -45,6 +45,7 @@ Column { @@ -45,6 +45,7 @@ Column {
property bool _hasModes: _camera && _camera && _camera.hasModes
property bool _videoRecording: _camera && _camera.videoStatus === QGCCameraControl.VIDEO_CAPTURE_STATUS_RUNNING
property bool _storageReady: _camera && _camera.storageStatus === QGCCameraControl.STORAGE_READY
property bool _batteryReady: _camera && _camera.batteryRemaining >= 0
property bool _storageIgnored: _camera && _camera.storageStatus === QGCCameraControl.STORAGE_NOT_SUPPORTED
property bool _canShoot: !_videoRecording && _cameraPhotoIdle && ((_storageReady && _camera.storageFree > 0) || _storageIgnored)
property int _curCameraIndex: _dynamicCameras ? _dynamicCameras.currentCamera : 0
@ -76,6 +77,12 @@ Column { @@ -76,6 +77,12 @@ Column {
anchors.horizontalCenter: parent.horizontalCenter
visible: _camera && _storageReady
}
QGCLabel {
text: _camera ? qsTr("Battery: ") + _camera.batteryRemainingStr : ""
font.pointSize: ScreenTools.smallFontPointSize
anchors.horizontalCenter: parent.horizontalCenter
visible: _camera && _batteryReady
}
//-- Camera Mode (visible only if camera has modes)
Item { width: 1; height: ScreenTools.defaultFontPixelHeight * 0.75; visible: camMode.visible; }
Rectangle {

Loading…
Cancel
Save