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
8def96f3
Commit
8def96f3
authored
Jan 06, 2019
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Camera now handles assigned joystick buttons for zoom and camera switching.
parent
d36a3905
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
68 additions
and
9 deletions
+68
-9
QGCCameraManager.cc
src/Camera/QGCCameraManager.cc
+56
-5
QGCCameraManager.h
src/Camera/QGCCameraManager.h
+12
-4
No files found.
src/Camera/QGCCameraManager.cc
View file @
8def96f3
...
...
@@ -7,20 +7,20 @@
#include "QGCApplication.h"
#include "QGCCameraManager.h"
#include "JoystickManager.h"
QGC_LOGGING_CATEGORY
(
CameraManagerLog
,
"CameraManagerLog"
)
//-----------------------------------------------------------------------------
QGCCameraManager
::
QGCCameraManager
(
Vehicle
*
vehicle
)
:
_vehicle
(
vehicle
)
,
_vehicleReadyState
(
false
)
,
_currentTask
(
0
)
,
_currentCamera
(
0
)
{
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
qCDebug
(
CameraManagerLog
)
<<
"QGCCameraManager Created"
;
connect
(
qgcApp
()
->
toolbox
()
->
multiVehicleManager
(),
&
MultiVehicleManager
::
parameterReadyVehicleAvailableChanged
,
this
,
&
QGCCameraManager
::
_vehicleReady
);
connect
(
_vehicle
,
&
Vehicle
::
mavlinkMessageReceived
,
this
,
&
QGCCameraManager
::
_mavlinkMessageReceived
);
_lastZoomChange
.
start
();
_lastCameraChange
.
start
();
}
//-----------------------------------------------------------------------------
...
...
@@ -46,6 +46,9 @@ QGCCameraManager::_vehicleReady(bool ready)
if
(
ready
)
{
if
(
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
activeVehicle
()
==
_vehicle
)
{
_vehicleReadyState
=
true
;
JoystickManager
*
pJoyMgr
=
qgcApp
()
->
toolbox
()
->
joystickManager
();
_activeJoystickChanged
(
pJoyMgr
->
activeJoystick
());
connect
(
pJoyMgr
,
&
JoystickManager
::
activeJoystickChanged
,
this
,
&
QGCCameraManager
::
_activeJoystickChanged
);
}
}
}
...
...
@@ -114,7 +117,7 @@ QGCCameraManager::_findCamera(int id)
}
}
qWarning
()
<<
"Camera component id not found:"
<<
id
;
return
NULL
;
return
nullptr
;
}
//-----------------------------------------------------------------------------
...
...
@@ -127,7 +130,7 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
_cameraInfoRequested
[
message
.
compid
]
=
false
;
mavlink_camera_information_t
info
;
mavlink_msg_camera_information_decode
(
&
message
,
&
info
);
qCDebug
(
CameraManagerLog
)
<<
"_handleCameraInfo:"
<<
(
const
char
*
)(
void
*
)
&
info
.
model_name
[
0
]
<<
(
const
char
*
)(
void
*
)
&
info
.
vendor_name
[
0
]
<<
"Comp ID:"
<<
message
.
compid
;
qCDebug
(
CameraManagerLog
)
<<
"_handleCameraInfo:"
<<
reinterpret_cast
<
const
char
*>
(
info
.
model_name
)
<<
reinterpret_cast
<
const
char
*>
(
info
.
vendor_name
)
<<
"Comp ID:"
<<
message
.
compid
;
QGCCameraControl
*
pCamera
=
_vehicle
->
firmwarePlugin
()
->
createCameraControl
(
&
info
,
_vehicle
,
message
.
compid
,
this
);
if
(
pCamera
)
{
QQmlEngine
::
setObjectOwnership
(
pCamera
,
QQmlEngine
::
CppOwnership
);
...
...
@@ -212,3 +215,51 @@ QGCCameraManager::_requestCameraInfo(int compID)
1
);
// Do Request
}
}
//----------------------------------------------------------------------------------------
void
QGCCameraManager
::
_activeJoystickChanged
(
Joystick
*
joystick
)
{
qCDebug
(
CameraManagerLog
)
<<
"Joystick changed"
;
if
(
_activeJoystick
)
{
disconnect
(
_activeJoystick
,
&
Joystick
::
stepZoom
,
this
,
&
QGCCameraManager
::
_stepZoom
);
disconnect
(
_activeJoystick
,
&
Joystick
::
stepCamera
,
this
,
&
QGCCameraManager
::
_stepCamera
);
}
_activeJoystick
=
joystick
;
if
(
_activeJoystick
)
{
connect
(
_activeJoystick
,
&
Joystick
::
stepZoom
,
this
,
&
QGCCameraManager
::
_stepZoom
);
connect
(
_activeJoystick
,
&
Joystick
::
stepCamera
,
this
,
&
QGCCameraManager
::
_stepCamera
);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager
::
_stepZoom
(
int
direction
)
{
if
(
_lastZoomChange
.
elapsed
()
>
250
)
{
_lastZoomChange
.
start
();
qCDebug
(
CameraManagerLog
)
<<
"Step Camera Zoom"
<<
direction
;
if
(
_cameras
.
count
()
&&
_cameras
[
_currentCamera
])
{
QGCCameraControl
*
pCamera
=
qobject_cast
<
QGCCameraControl
*>
(
_cameras
[
_currentCamera
]);
if
(
pCamera
)
{
pCamera
->
stepZoom
(
direction
);
}
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager
::
_stepCamera
(
int
direction
)
{
if
(
_lastCameraChange
.
elapsed
()
>
1000
)
{
_lastCameraChange
.
start
();
qCDebug
(
CameraManagerLog
)
<<
"Step Camera"
<<
direction
;
int
c
=
_currentCamera
+
direction
;
if
(
c
<
0
)
c
=
_cameras
.
count
()
-
1
;
if
(
c
>=
_cameras
.
count
())
c
=
0
;
setCurrentCamera
(
c
);
}
}
src/Camera/QGCCameraManager.h
View file @
8def96f3
...
...
@@ -17,6 +17,8 @@
Q_DECLARE_LOGGING_CATEGORY
(
CameraManagerLog
)
class
Joystick
;
//-----------------------------------------------------------------------------
class
QGCCameraManager
:
public
QObject
{
...
...
@@ -46,6 +48,9 @@ signals:
protected
slots
:
virtual
void
_vehicleReady
(
bool
ready
);
virtual
void
_mavlinkMessageReceived
(
const
mavlink_message_t
&
message
);
virtual
void
_activeJoystickChanged
(
Joystick
*
joystick
);
virtual
void
_stepZoom
(
int
direction
);
virtual
void
_stepCamera
(
int
direction
);
protected:
virtual
QGCCameraControl
*
_findCamera
(
int
id
);
...
...
@@ -59,11 +64,14 @@ protected:
virtual
void
_handleCaptureStatus
(
const
mavlink_message_t
&
message
);
protected:
Vehicle
*
_vehicle
;
bool
_vehicleReadyState
;
int
_currentTask
;
Vehicle
*
_vehicle
=
nullptr
;
Joystick
*
_activeJoystick
=
nullptr
;
bool
_vehicleReadyState
=
false
;
int
_currentTask
=
0
;
QmlObjectListModel
_cameras
;
QStringList
_cameraLabels
;
QMap
<
int
,
bool
>
_cameraInfoRequested
;
int
_currentCamera
;
int
_currentCamera
=
0
;
QTime
_lastZoomChange
;
QTime
_lastCameraChange
;
};
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