Commit e1a936e7 authored by Gus Grubba's avatar Gus Grubba

Remove test URL

parent 5a39cfd4
...@@ -115,14 +115,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh ...@@ -115,14 +115,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
, _cameraMode(CAMERA_MODE_UNDEFINED) , _cameraMode(CAMERA_MODE_UNDEFINED)
, _video_status(VIDEO_CAPTURE_STATUS_UNDEFINED) , _video_status(VIDEO_CAPTURE_STATUS_UNDEFINED)
{ {
memcpy(&_info, &info, sizeof(mavlink_camera_information_t)); _processCameraInfo(info);
connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady);
if(1 /*_info.cam_definition_uri[0]*/) {
//-- Process camera definition file
_httpRequest("http://www.grubba.com/e90.xml");
} else {
_initWhenReady();
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -139,6 +132,21 @@ QGCCameraControl::~QGCCameraControl() ...@@ -139,6 +132,21 @@ QGCCameraControl::~QGCCameraControl()
} }
} }
//-----------------------------------------------------------------------------
void
QGCCameraControl::_processCameraInfo(const mavlink_camera_information_t* info)
{
memcpy(&_info, &info, sizeof(mavlink_camera_information_t));
connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady);
if(_info.cam_definition_uri[0]) {
//-- Process camera definition file
const char* url = (const char*)info->cam_definition_uri;
_httpRequest(url);
} else {
_initWhenReady();
}
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCCameraControl::_initWhenReady() QGCCameraControl::_initWhenReady()
......
...@@ -155,6 +155,7 @@ signals: ...@@ -155,6 +155,7 @@ signals:
protected: protected:
virtual void _setVideoStatus (VideoStatus status); virtual void _setVideoStatus (VideoStatus status);
virtual void _setCameraMode (CameraMode mode); virtual void _setCameraMode (CameraMode mode);
virtual void _processCameraInfo (const mavlink_camera_information_t* info);
private slots: private slots:
void _initWhenReady (); void _initWhenReady ();
......
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