Unverified Commit 151ce31f authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #7083 from mavlink/autoVideoStream

Auto video stream
parents 351cff6d b8ad6544
......@@ -58,6 +58,27 @@ static const char* kPhotoMode = "PhotoMode";
static const char* kPhotoLapse = "PhotoLapse";
static const char* kPhotoLapseCount = "PhotoLapseCount";
//-----------------------------------------------------------------------------
QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_)
: QObject(parent)
, param(param_)
, value(value_)
, exclusions(exclusions_)
{
}
//-----------------------------------------------------------------------------
QGCCameraOptionRange::QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_)
: QObject(parent)
, param(param_)
, value(value_)
, targetParam(targetParam_)
, condition(condition_)
, optNames(optNames_)
, optValues(optValues_)
{
}
//-----------------------------------------------------------------------------
static bool
read_attribute(QDomNode& node, const char* tagName, bool& target)
......@@ -127,7 +148,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
, _cached(false)
, _storageFree(0)
, _storageTotal(0)
, _netManager(NULL)
, _netManager(nullptr)
, _cameraMode(CAM_MODE_UNDEFINED)
, _photoMode(PHOTO_CAPTURE_SINGLE)
, _photoLapse(1.0)
......@@ -140,9 +161,9 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
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]);
_modelName = QString((const char*)(void*)&info->model_name[0]);
int ver = (int)_info.cam_definition_version;
_vendor = QString(reinterpret_cast<const char*>(info->vendor_name));
_modelName = QString(reinterpret_cast<const char*>(info->model_name));
int ver = static_cast<int>(_info.cam_definition_version);
_cacheFile.sprintf("%s/%s_%s_%03d.xml",
qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(),
_vendor.toStdString().c_str(),
......@@ -155,7 +176,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
_initWhenReady();
}
QSettings settings;
_photoMode = (PhotoMode)settings.value(kPhotoMode, (int)PHOTO_CAPTURE_SINGLE).toInt();
_photoMode = static_cast<PhotoMode>(settings.value(kPhotoMode, static_cast<int>(PHOTO_CAPTURE_SINGLE)).toInt());
_photoLapse = settings.value(kPhotoLapse, 1.0).toDouble();
_photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt();
}
......@@ -189,7 +210,7 @@ QGCCameraControl::_initWhenReady()
emit infoChanged();
if(_netManager) {
delete _netManager;
_netManager = NULL;
_netManager = nullptr;
}
}
......@@ -223,7 +244,7 @@ QGCCameraControl::photoStatus()
QString
QGCCameraControl::storageFreeStr()
{
return QGCMapEngine::bigSizeToString((quint64)_storageFree * 1024 * 1024);
return QGCMapEngine::bigSizeToString(static_cast<quint64>(_storageFree * 1024 * 1024));
}
//-----------------------------------------------------------------------------
......@@ -247,7 +268,7 @@ QGCCameraControl::setPhotoMode(PhotoMode mode)
{
_photoMode = mode;
QSettings settings;
settings.setValue(kPhotoMode, (int)mode);
settings.setValue(kPhotoMode, static_cast<int>(mode));
emit photoModeChanged();
}
......@@ -312,12 +333,12 @@ QGCCameraControl::takePhoto()
}
if(capturesPhotos()) {
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_IMAGE_START_CAPTURE, // Command id
false, // ShowError
0, // Reserved (Set to 0)
_photoMode == PHOTO_CAPTURE_SINGLE ? 0 : _photoLapse, // Duration between two consecutive pictures (in seconds--ignored if single image)
_photoMode == PHOTO_CAPTURE_SINGLE ? 1 : _photoLapseCount); // Number of images to capture total - 0 for unlimited capture
_compID, // Target component
MAV_CMD_IMAGE_START_CAPTURE, // Command id
false, // ShowError
0, // Reserved (Set to 0)
static_cast<float>(_photoMode == PHOTO_CAPTURE_SINGLE ? 0 : _photoLapse), // Duration between two consecutive pictures (in seconds--ignored if single image)
_photoMode == PHOTO_CAPTURE_SINGLE ? 1 : _photoLapseCount); // Number of images to capture total - 0 for unlimited capture
_setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS);
_captureInfoRetries = 0;
//-- Capture local image as well
......@@ -944,12 +965,12 @@ QGCCameraControl::_requestAllParameters()
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_message_t msg;
mavlink_msg_param_ext_request_list_pack_chan(
mavlink->getSystemId(),
mavlink->getComponentId(),
static_cast<uint8_t>(mavlink->getSystemId()),
static_cast<uint8_t>(mavlink->getComponentId()),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
_vehicle->id(),
compID());
static_cast<uint8_t>(_vehicle->id()),
static_cast<uint8_t>(compID()));
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
qCDebug(CameraControlLogVerbose) << "Request all parameters";
}
......@@ -1223,7 +1244,7 @@ void
QGCCameraControl::handleSettings(const mavlink_camera_settings_t& settings)
{
qCDebug(CameraControlLog) << "handleSettings() Mode:" << settings.mode_id;
_setCameraMode((CameraMode)settings.mode_id);
_setCameraMode(static_cast<CameraMode>(settings.mode_id));
}
//-----------------------------------------------------------------------------
......@@ -1231,13 +1252,15 @@ void
QGCCameraControl::handleStorageInfo(const mavlink_storage_information_t& st)
{
qCDebug(CameraControlLog) << "_handleStorageInfo:" << st.available_capacity << st.status << st.storage_count << st.storage_id << st.total_capacity << st.used_capacity;
if(_storageTotal != st.total_capacity) {
_storageTotal = st.total_capacity;
uint32_t t = static_cast<uint32_t>(st.total_capacity);
if(_storageTotal != t) {
_storageTotal = t;
}
//-- Always emit this
emit storageTotalChanged();
if(_storageFree != st.available_capacity) {
_storageFree = st.available_capacity;
uint32_t a = static_cast<uint32_t>(st.available_capacity);
if(_storageFree != a) {
_storageFree = a;
emit storageFreeChanged();
}
}
......@@ -1249,15 +1272,16 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap
//-- This is a response to MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS
qCDebug(CameraControlLog) << "handleCaptureStatus:" << cap.available_capacity << cap.image_interval << cap.image_status << cap.recording_time_ms << cap.video_status;
//-- Disk Free Space
if(_storageFree != cap.available_capacity) {
_storageFree = cap.available_capacity;
uint32_t a = static_cast<uint32_t>(cap.available_capacity);
if(_storageFree != a) {
_storageFree = a;
emit storageFreeChanged();
}
//-- Video/Image Capture Status
uint8_t vs = cap.video_status < (uint8_t)VIDEO_CAPTURE_STATUS_LAST ? cap.video_status : (uint8_t)VIDEO_CAPTURE_STATUS_UNDEFINED;
uint8_t ps = cap.image_status < (uint8_t)PHOTO_CAPTURE_LAST ? cap.image_status : (uint8_t)PHOTO_CAPTURE_STATUS_UNDEFINED;
_setVideoStatus((VideoStatus)vs);
_setPhotoStatus((PhotoStatus)ps);
uint8_t vs = cap.video_status < static_cast<uint8_t>(VIDEO_CAPTURE_STATUS_LAST) ? cap.video_status : static_cast<uint8_t>(VIDEO_CAPTURE_STATUS_UNDEFINED);
uint8_t ps = cap.image_status < static_cast<uint8_t>(PHOTO_CAPTURE_LAST) ? cap.image_status : static_cast<uint8_t>(PHOTO_CAPTURE_STATUS_UNDEFINED);
_setVideoStatus(static_cast<VideoStatus>(vs));
_setPhotoStatus(static_cast<PhotoStatus>(ps));
//-- Keep asking for it once in a while when recording
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
_captureStatusTimer.start(5000);
......
......@@ -21,13 +21,7 @@ Q_DECLARE_LOGGING_CATEGORY(CameraControlLogVerbose)
class QGCCameraOptionExclusion : public QObject
{
public:
QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_)
: QObject(parent)
, param(param_)
, value(value_)
, exclusions(exclusions_)
{
}
QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_);
QString param;
QString value;
QStringList exclusions;
......@@ -37,16 +31,7 @@ public:
class QGCCameraOptionRange : public QObject
{
public:
QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_)
: QObject(parent)
, param(param_)
, value(value_)
, targetParam(targetParam_)
, condition(condition_)
, optNames(optNames_)
, optValues(optValues_)
{
}
QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_);
QString param;
QString value;
QString targetParam;
......@@ -62,7 +47,7 @@ class QGCCameraControl : public FactGroup
Q_OBJECT
friend class QGCCameraParamIO;
public:
QGCCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL);
QGCCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = nullptr);
virtual ~QGCCameraControl();
//-- cam_mode
......@@ -142,8 +127,8 @@ public:
virtual QString modelName () { return _modelName; }
virtual QString vendor () { return _vendor; }
virtual QString firmwareVersion ();
virtual qreal focalLength () { return (qreal)_info.focal_length; }
virtual QSizeF sensorSize () { return QSizeF(_info.sensor_size_h, _info.sensor_size_v); }
virtual qreal focalLength () { return static_cast<qreal>(_info.focal_length); }
virtual QSizeF sensorSize () { return QSizeF(static_cast<qreal>(_info.sensor_size_h), static_cast<qreal>(_info.sensor_size_v)); }
virtual QSize resolution () { return QSize(_info.resolution_h, _info.resolution_v); }
virtual bool capturesVideo () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO; }
virtual bool capturesPhotos () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_IMAGE; }
......
......@@ -22,7 +22,7 @@ import QGroundControl.Controllers 1.0
Item {
id: root
property double _ar: QGroundControl.settingsManager.videoSettings.aspectRatio.rawValue
property double _ar: QGroundControl.videoManager.aspectRatio
property bool _showGrid: QGroundControl.settingsManager.videoSettings.gridLines.rawValue > 0
property var _videoReceiver: QGroundControl.videoManager.videoReceiver
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
......
......@@ -25,7 +25,9 @@
#include "QGCToolbox.h"
#include "QGCCorePlugin.h"
#include "QGCOptions.h"
#include "MultiVehicleManager.h"
#include "Settings/SettingsManager.h"
#include "Vehicle.h"
QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")
......@@ -35,6 +37,7 @@ VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
, _videoReceiver(nullptr)
, _videoSettings(nullptr)
, _fullScreen(false)
, _activeVehicle(nullptr)
{
}
......@@ -61,6 +64,9 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
connect(_videoSettings->udpPort(), &Fact::rawValueChanged, this, &VideoManager::_udpPortChanged);
connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_rtspUrlChanged);
connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_tcpUrlChanged);
connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::_aspectRatioChanged);
MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle);
#if defined(QGC_GST_STREAMING)
#ifndef QGC_DISABLE_UVC
......@@ -81,6 +87,19 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
#endif
}
//-----------------------------------------------------------------------------
double VideoManager::aspectRatio()
{
if(isAutoStream()) {
if(_streamInfo.resolution_h && _streamInfo.resolution_v) {
return static_cast<double>(_streamInfo.resolution_h) / static_cast<double>(_streamInfo.resolution_v);
}
return 1.0;
} else {
return _videoSettings->aspectRatio()->rawValue().toDouble();
}
}
//-----------------------------------------------------------------------------
void
VideoManager::_updateUVC()
......@@ -106,6 +125,7 @@ VideoManager::_videoSourceChanged()
_updateUVC();
emit hasVideoChanged();
emit isGStreamerChanged();
emit isAutoStreamChanged();
_restartVideo();
}
......@@ -144,7 +164,23 @@ VideoManager::isGStreamer()
{
#if defined(QGC_GST_STREAMING)
QString videoSource = _videoSettings->videoSource()->rawValue().toString();
return videoSource == VideoSettings::videoSourceUDP || videoSource == VideoSettings::videoSourceRTSP || videoSource == VideoSettings::videoSourceTCP;
return
videoSource == VideoSettings::videoSourceUDP ||
videoSource == VideoSettings::videoSourceRTSP ||
videoSource == VideoSettings::videoSourceAuto ||
videoSource == VideoSettings::videoSourceTCP;
#else
return false;
#endif
}
//-----------------------------------------------------------------------------
bool
VideoManager::isAutoStream()
{
#if defined(QGC_GST_STREAMING)
QString videoSource = _videoSettings->videoSource()->rawValue().toString();
return videoSource == VideoSettings::videoSourceAuto;
#else
return false;
#endif
......@@ -171,6 +207,8 @@ VideoManager::_updateSettings()
_videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString());
else if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceTCP)
_videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
else if (isAutoStream())
_videoReceiver->setUri(QString(_streamInfo.uri));
}
//-----------------------------------------------------------------------------
......@@ -185,3 +223,47 @@ VideoManager::_restartVideo()
_videoReceiver->start();
#endif
}
//----------------------------------------------------------------------------------------
void
VideoManager::_setActiveVehicle(Vehicle* vehicle)
{
if(_activeVehicle) {
disconnect(_activeVehicle, &Vehicle::mavlinkMessageReceived, this, &VideoManager::_vehicleMessageReceived);
}
_activeVehicle = vehicle;
if(_activeVehicle) {
if(isAutoStream()) {
_videoReceiver->stop();
}
//-- Video Stream Discovery
connect(_activeVehicle, &Vehicle::mavlinkMessageReceived, this, &VideoManager::_vehicleMessageReceived);
qCDebug(VideoManagerLog) << "Requesting video stream info";
_activeVehicle->sendMavCommand(
MAV_COMP_ID_ALL, // Target component
MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, // Command id
false, // ShowError
1, // First camera only
0); // Reserved (Set to 0)
}
}
//----------------------------------------------------------------------------------------
void
VideoManager::_vehicleMessageReceived(const mavlink_message_t& message)
{
//-- For now we only handle one stream. There is no UI to pick different streams.
if(message.msgid == MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION) {
mavlink_msg_video_stream_information_decode(&message, &_streamInfo);
qCDebug(VideoManagerLog) << "Received video stream info:" << _streamInfo.uri;
_restartVideo();
emit aspectRatioChanged();
}
}
//----------------------------------------------------------------------------------------
void
VideoManager::_aspectRatioChanged()
{
emit aspectRatioChanged();
}
......@@ -15,6 +15,7 @@
#include <QTimer>
#include <QUrl>
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
#include "VideoReceiver.h"
#include "QGCToolbox.h"
......@@ -22,6 +23,7 @@
Q_DECLARE_LOGGING_CATEGORY(VideoManagerLog)
class VideoSettings;
class Vehicle;
class VideoManager : public QGCTool
{
......@@ -33,15 +35,20 @@ public:
Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged)
Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged)
Q_PROPERTY(bool isAutoStream READ isAutoStream NOTIFY isAutoStreamChanged)
Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged)
Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT)
Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged)
Q_PROPERTY(VideoReceiver* videoReceiver READ videoReceiver CONSTANT)
Q_PROPERTY(double aspectRatio READ aspectRatio NOTIFY aspectRatioChanged)
bool hasVideo ();
bool isGStreamer ();
bool isAutoStream ();
bool fullScreen () { return _fullScreen; }
QString videoSourceID () { return _videoSourceID; }
QString autoURL () { return QString(_streamInfo.uri); }
double aspectRatio ();
VideoReceiver* videoReceiver () { return _videoReceiver; }
......@@ -64,6 +71,8 @@ signals:
void isGStreamerChanged ();
void videoSourceIDChanged ();
void fullScreenChanged ();
void isAutoStreamChanged ();
void aspectRatioChanged ();
private slots:
void _videoSourceChanged ();
......@@ -71,6 +80,9 @@ private slots:
void _rtspUrlChanged ();
void _tcpUrlChanged ();
void _updateUVC ();
void _aspectRatioChanged ();
void _setActiveVehicle (Vehicle* vehicle);
void _vehicleMessageReceived (const mavlink_message_t& message);
private:
void _updateSettings ();
......@@ -80,6 +92,8 @@ private:
VideoSettings* _videoSettings;
QString _videoSourceID;
bool _fullScreen;
Vehicle* _activeVehicle;
mavlink_video_stream_information_t _streamInfo;
};
#endif
......@@ -8,6 +8,8 @@
****************************************************************************/
#include "VideoSettings.h"
#include "QGCApplication.h"
#include "VideoManager.h"
#include <QQmlEngine>
#include <QtQml>
......@@ -17,14 +19,12 @@
#include <QCameraInfo>
#endif
const char* VideoSettings::videoSourceNoVideo = "No Video Available";
const char* VideoSettings::videoDisabled = "Video Stream Disabled";
const char* VideoSettings::videoSourceUDP = "UDP Video Stream";
const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream";
const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream";
#ifdef QGC_GST_TAISYNC_USB
const char* VideoSettings::videoSourceTaiSyncUSB = "Taisync USB";
#endif
const char* VideoSettings::videoSourceNoVideo = "No Video Available";
const char* VideoSettings::videoDisabled = "Video Stream Disabled";
const char* VideoSettings::videoSourceAuto = "Automatic Video Stream";
const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream";
const char* VideoSettings::videoSourceUDP = "UDP Video Stream";
const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream";
DECLARE_SETTINGGROUP(Video, "Video")
{
......@@ -34,14 +34,12 @@ DECLARE_SETTINGGROUP(Video, "Video")
// Setup enum values for videoSource settings into meta data
QStringList videoSourceList;
#ifdef QGC_GST_STREAMING
videoSourceList.append(videoSourceAuto);
videoSourceList.append(videoSourceRTSP);
#ifndef NO_UDP_VIDEO
videoSourceList.append(videoSourceUDP);
#endif
videoSourceList.append(videoSourceRTSP);
videoSourceList.append(videoSourceTCP);
#ifdef QGC_GST_TAISYNC_USB
videoSourceList.append(videoSourceTaiSyncUSB);
#endif
#endif
#ifndef QGC_DISABLE_UVC
QList<QCameraInfo> cameras = QCameraInfo::availableCameras();
......@@ -60,7 +58,6 @@ DECLARE_SETTINGGROUP(Video, "Video")
videoSourceVarList.append(QVariant::fromValue(videoSource));
}
_nameToMetaDataMap[videoSourceName]->setEnumInfo(videoSourceList, videoSourceVarList);
// Set default value for videoSource
_setDefaults();
}
......@@ -138,23 +135,26 @@ bool VideoSettings::streamConfigured(void)
if(vSource == videoSourceNoVideo || vSource == videoDisabled) {
return false;
}
#ifdef QGC_GST_TAISYNC_USB
if(vSource == videoSourceTaiSyncUSB) {
return true;
}
#endif
//-- If UDP, check if port is set
if(vSource == videoSourceUDP) {
qCDebug(VideoManagerLog) << "Testing configuration for UDP Stream:" << udpPort()->rawValue().toInt();
return udpPort()->rawValue().toInt() != 0;
}
//-- If RTSP, check for URL
if(vSource == videoSourceRTSP) {
qCDebug(VideoManagerLog) << "Testing configuration for RTSP Stream:" << rtspUrl()->rawValue().toString();
return !rtspUrl()->rawValue().toString().isEmpty();
}
//-- If TCP, check for URL
if(vSource == videoSourceTCP) {
qCDebug(VideoManagerLog) << "Testing configuration for TCP Stream:" << tcpUrl()->rawValue().toString();
return !tcpUrl()->rawValue().toString().isEmpty();
}
//-- If Auto, check for received URL
if(vSource == videoSourceAuto) {
qCDebug(VideoManagerLog) << "Testing configuration for Auto Stream:" << qgcApp()->toolbox()->videoManager()->autoURL();
return !qgcApp()->toolbox()->videoManager()->autoURL().isEmpty();
}
return false;
}
......
......@@ -35,18 +35,24 @@ public:
DEFINE_SETTINGFACT(streamEnabled)
DEFINE_SETTINGFACT(disableWhenDisarmed)
Q_PROPERTY(bool streamConfigured READ streamConfigured NOTIFY streamConfiguredChanged)
Q_PROPERTY(bool streamConfigured READ streamConfigured NOTIFY streamConfiguredChanged)
Q_PROPERTY(QString autoVideoSource READ autoVideoSource CONSTANT)
Q_PROPERTY(QString rtspVideoSource READ rtspVideoSource CONSTANT)
Q_PROPERTY(QString udpVideoSource READ udpVideoSource CONSTANT)
Q_PROPERTY(QString tcpVideoSource READ tcpVideoSource CONSTANT)
bool streamConfigured ();
bool streamConfigured ();
QString autoVideoSource () { return videoSourceAuto; }
QString rtspVideoSource () { return videoSourceRTSP; }
QString udpVideoSource () { return videoSourceUDP; }
QString tcpVideoSource () { return videoSourceTCP; }
static const char* videoSourceNoVideo;
static const char* videoDisabled;
static const char* videoSourceUDP;
static const char* videoSourceRTSP;
static const char* videoSourceAuto;
static const char* videoSourceTCP;
#ifdef QGC_GST_TAISYNC_USB
static const char* videoSourceTaiSyncUSB;
#endif
signals:
void streamConfiguredChanged ();
......
......@@ -501,7 +501,7 @@ public:
Vehicle(MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType,
FirmwarePluginManager* firmwarePluginManager,
QObject* parent = NULL);
QObject* parent = nullptr);
~Vehicle();
......@@ -892,9 +892,9 @@ public:
QString formatedMessages ();
QString formatedMessage () { return _formatedMessage; }
QString latestError () { return _latestError; }
float latitude () { return _coordinate.latitude(); }
float longitude () { return _coordinate.longitude(); }
bool mavPresent () { return _mav != NULL; }
float latitude () { return static_cast<float>(_coordinate.latitude()); }
float longitude () { return static_cast<float>(_coordinate.longitude()); }
bool mavPresent () { return _mav != nullptr; }
int rcRSSI () { return _rcRSSI; }
bool px4Firmware () const { return _firmwareType == MAV_AUTOPILOT_PX4; }
bool apmFirmware () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
......@@ -990,8 +990,19 @@ public:
void sendMavCommandInt(int component, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7);
/// Same as sendMavCommand but available from Qml.
Q_INVOKABLE void sendCommand(int component, int command, bool showError, double param1 = 0.0f, double param2 = 0.0f, double param3 = 0.0f, double param4 = 0.0f, double param5 = 0.0f, double param6 = 0.0f, double param7 = 0.0f)
{ sendMavCommand(component, (MAV_CMD)command, showError, param1, param2, param3, param4, param5, param6, param7); }
Q_INVOKABLE void sendCommand(int component, int command, bool showError, double param1 = 0.0, double param2 = 0.0, double param3 = 0.0, double param4 = 0.0, double param5 = 0.0, double param6 = 0.0, double param7 = 0.0)
{
sendMavCommand(
component, static_cast<MAV_CMD>(command),
showError,
static_cast<float>(param1),
static_cast<float>(param2),
static_cast<float>(param3),
static_cast<float>(param4),
static_cast<float>(param5),
static_cast<float>(param6),
static_cast<float>(param7));
}
int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
......
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment