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
25d43fd7
Commit
25d43fd7
authored
Jul 21, 2017
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
MAVLink cleanup
parent
5856f869
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
31 additions
and
39 deletions
+31
-39
v2.0
libs/mavlink/include/mavlink/v2.0
+1
-1
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+7
-11
QGCCameraManager.cc
src/Camera/QGCCameraManager.cc
+1
-4
QGCCameraManager.h
src/Camera/QGCCameraManager.h
+0
-1
CameraSection.cc
src/MissionManager/CameraSection.cc
+6
-6
CameraSectionTest.cc
src/MissionManager/CameraSectionTest.cc
+10
-10
MavCmdInfoCommon.json
src/MissionManager/MavCmdInfoCommon.json
+5
-5
SurveyMissionItem.cc
src/MissionManager/SurveyMissionItem.cc
+1
-1
No files found.
v2.0
@
0b881137
Subproject commit 0
5c8fa042e67888f98ce63e2a76bb35f38dd218f
Subproject commit 0
b8811377674320acd37d6b8e1a2945133528f14
src/Camera/QGCCameraControl.cc
View file @
25d43fd7
...
...
@@ -120,10 +120,9 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
{
memcpy
(
&
_info
,
&
info
,
sizeof
(
mavlink_camera_information_t
));
connect
(
this
,
&
QGCCameraControl
::
dataReady
,
this
,
&
QGCCameraControl
::
_dataReady
);
const
char
*
url
=
(
const
char
*
)
info
->
cam_definition_uri
;
if
(
url
[
0
]
!=
0
)
{
if
(
info
->
cam_definition_uri
[
0
]
!=
0
)
{
//-- Process camera definition file
_handleDefinitionFile
(
url
);
_handleDefinitionFile
(
info
->
cam_definition_uri
);
}
else
{
_initWhenReady
();
}
...
...
@@ -253,7 +252,7 @@ QGCCameraControl::takePhoto()
MAV_COMP_ID_CAMERA
,
// Target component
MAV_CMD_IMAGE_START_CAPTURE
,
// Command id
false
,
// ShowError
0
,
//
Camera ID (0 for all cameras), 1 for first, 2 for second, etc.
0
,
//
Reserved (Set to 0)
0
,
// Duration between two consecutive pictures (in seconds--ignored if single image)
1
);
// Number of images to capture total - 0 for unlimited capture
//-- Capture local image as well
...
...
@@ -280,7 +279,7 @@ QGCCameraControl::startVideo()
MAV_COMP_ID_CAMERA
,
// Target component
MAV_CMD_VIDEO_START_CAPTURE
,
// Command id
true
,
// ShowError
0
,
//
Camera ID (0 for all cameras), 1 for first, 2 for second, etc.
0
,
//
Reserved (Set to 0)
0
);
// CAMERA_CAPTURE_STATUS Frequency
return
true
;
}
...
...
@@ -297,7 +296,7 @@ QGCCameraControl::stopVideo()
MAV_COMP_ID_CAMERA
,
// Target component
MAV_CMD_VIDEO_STOP_CAPTURE
,
// Command id
true
,
// ShowError
0
);
//
Camera ID (0 for all cameras), 1 for first, 2 for second, etc.
0
);
//
Reserved (Set to 0)
return
true
;
}
return
false
;
...
...
@@ -314,7 +313,7 @@ QGCCameraControl::setVideoMode()
_compID
,
// Target component
MAV_CMD_SET_CAMERA_MODE
,
// Command id
true
,
// ShowError
0
,
//
Camera ID (0 for all, 1 for first, 2 for second, etc.) ==> TODO: Remove
0
,
//
Reserved (Set to 0)
CAMERA_MODE_VIDEO
);
// Camera mode (0: photo, 1: video)
_setCameraMode
(
CAMERA_MODE_VIDEO
);
}
...
...
@@ -331,7 +330,7 @@ QGCCameraControl::setPhotoMode()
_compID
,
// Target component
MAV_CMD_SET_CAMERA_MODE
,
// Command id
true
,
// ShowError
0
,
//
Camera ID (0 for all, 1 for first, 2 for second, etc.) ==> TODO: Remove
0
,
//
Reserved (Set to 0)
CAMERA_MODE_PHOTO
);
// Camera mode (0: photo, 1: video)
_setCameraMode
(
CAMERA_MODE_PHOTO
);
}
...
...
@@ -346,7 +345,6 @@ QGCCameraControl::resetSettings()
_compID
,
// Target component
MAV_CMD_RESET_CAMERA_SETTINGS
,
// Command id
true
,
// ShowError
0
,
// Camera ID (0 for all, 1 for first, 2 for second, etc.) ==> TODO: Remove
1
);
// Do Reset
}
...
...
@@ -373,7 +371,6 @@ QGCCameraControl::_requestCaptureStatus()
_compID
,
// target component
MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS
,
// command id
false
,
// showError
0
,
// Storage ID ("All" for now)
1
);
// Do Request
}
...
...
@@ -897,7 +894,6 @@ QGCCameraControl::_requestCameraSettings()
_compID
,
// Target component
MAV_CMD_REQUEST_CAMERA_SETTINGS
,
// command id
false
,
// showError
0
,
// Camera ID (0 for all, 1 for first, 2 for second, etc.) ==> TODO: Remove
1
);
// Do Request
}
}
...
...
src/Camera/QGCCameraManager.cc
View file @
25d43fd7
...
...
@@ -14,7 +14,6 @@ QGC_LOGGING_CATEGORY(CameraManagerLog, "CameraManagerLog")
QGCCameraManager
::
QGCCameraManager
(
Vehicle
*
vehicle
)
:
_vehicle
(
vehicle
)
,
_vehicleReadyState
(
false
)
,
_cameraCount
(
0
)
,
_currentTask
(
0
)
{
qCDebug
(
CameraManagerLog
)
<<
"QGCCameraManager Created"
;
...
...
@@ -109,7 +108,7 @@ QGCCameraManager::_findCamera(int id)
}
}
}
qWarning
()
<<
"Camera id not found:"
<<
id
;
qWarning
()
<<
"Camera
component
id not found:"
<<
id
;
return
NULL
;
}
...
...
@@ -120,7 +119,6 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
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
];
_cameraCount
=
info
.
camera_count
;
QGCCameraControl
*
pCamera
=
_vehicle
->
firmwarePlugin
()
->
createCameraControl
(
&
info
,
_vehicle
,
message
.
compid
,
this
);
if
(
pCamera
)
{
_cameras
.
append
(
pCamera
);
...
...
@@ -198,7 +196,6 @@ QGCCameraManager::_requestCameraInfo(int compID)
compID
,
// target component
MAV_CMD_REQUEST_CAMERA_INFORMATION
,
// command id
false
,
// showError
0
,
// Camera ID (0 for all, 1 for first, 2 for second, etc.)
1
);
// Do Request
}
}
src/Camera/QGCCameraManager.h
View file @
25d43fd7
...
...
@@ -55,7 +55,6 @@ protected:
protected:
Vehicle
*
_vehicle
;
bool
_vehicleReadyState
;
int
_cameraCount
;
int
_currentTask
;
QmlObjectListModel
_cameras
;
QMap
<
int
,
bool
>
_cameraInfoRequested
;
...
...
src/MissionManager/CameraSection.cc
View file @
25d43fd7
...
...
@@ -119,7 +119,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
MissionItem
*
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_SET_CAMERA_MODE
,
MAV_FRAME_MISSION
,
0
,
//
camera id, all cameras
0
,
//
Reserved (Set to 0)
_cameraModeFact
.
rawValue
().
toDouble
(),
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 reserved
true
,
// autoContinue
...
...
@@ -151,7 +151,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_IMAGE_START_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
//
Camera ID, all cameras
0
,
//
Reserved (Set to 0)
_cameraPhotoIntervalTimeFact
.
rawValue
().
toInt
(),
// Interval
0
,
// Unlimited photo count
NAN
,
NAN
,
NAN
,
NAN
,
// param 4-7 reserved
...
...
@@ -177,7 +177,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_VIDEO_START_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
//
camera id = 0, all cameras
0
,
//
Reserved (Set to 0)
0
,
// No CAMERA_CAPTURE_STATUS streaming
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 reserved
true
,
// autoContinue
...
...
@@ -189,7 +189,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_VIDEO_STOP_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
//
Camera ID, all cameras
0
,
//
Reserved (Set to 0)
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 2-7 reserved
true
,
// autoContinue
false
,
// isCurrentItem
...
...
@@ -209,7 +209,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_IMAGE_STOP_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
//
camera id, all cameras
0
,
//
Reserved (Set to 0)
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 2-7 reserved
true
,
// autoContinue
false
,
// isCurrentItem
...
...
@@ -220,7 +220,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_IMAGE_START_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
//
camera id = 0, all cameras
0
,
//
Reserved (Set to 0)
0
,
// Interval (none)
1
,
// Take 1 photo
NAN
,
NAN
,
NAN
,
NAN
,
// param 4-7 reserved
...
...
src/MissionManager/CameraSectionTest.cc
View file @
25d43fd7
...
...
@@ -63,7 +63,7 @@ void CameraSectionTest::init(void)
MissionItem
(
0
,
// sequence number
MAV_CMD_VIDEO_START_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
//
camera id = 0, all cameras
0
,
//
Reserved (Set to 0)
0
,
// No CAMERA_CAPTURE_STATUS streaming
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 reserved
true
,
// autocontinue
...
...
@@ -82,7 +82,7 @@ void CameraSectionTest::init(void)
MissionItem
(
0
,
// sequence number
MAV_CMD_SET_CAMERA_MODE
,
MAV_FRAME_MISSION
,
0
,
//
camera id = 0, all cameras
0
,
//
Reserved (Set to 0)
CameraSection
::
CameraModePhoto
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 reserved
true
,
// autocontinue
...
...
@@ -92,7 +92,7 @@ void CameraSectionTest::init(void)
MissionItem
(
0
,
// sequence number
MAV_CMD_SET_CAMERA_MODE
,
MAV_FRAME_MISSION
,
0
,
//
camera id = 0, all cameras
0
,
//
Reserved (Set to 0)
CameraSection
::
CameraModeVideo
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 reserved
true
,
// autocontinue
...
...
@@ -102,7 +102,7 @@ void CameraSectionTest::init(void)
MissionItem
(
0
,
MAV_CMD_IMAGE_START_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
//
camera id = 0, all cameras
0
,
//
Reserved (Set to 0)
0
,
// Interval (none)
1
,
// Take 1 photo
NAN
,
NAN
,
NAN
,
NAN
,
// param 4-7 reserved
...
...
@@ -673,7 +673,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
/*
MAV_CMD_SET_CAMERA_MODE
Mission Param #1
Camera ID (0 for all cameras, 1 for first, 2 for second, etc.
)
Mission Param #1
Reserved (Set to 0
)
Mission Param #2 Camera mode (0: photo mode, 1: video mode)
Mission Param #3 Reserved (all remaining params)
*/
...
...
@@ -700,7 +700,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
/*
MAV_CMD_IMAGE_START_CAPTURE WIP: Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture.
Mission Param #1
Camera ID (0 for all cameras, 1 for first, 2 for second, etc.
)
Mission Param #1
Reserved (Set to 0
)
Mission Param #2 Duration between two consecutive pictures (in seconds)
Mission Param #3 Number of images to capture total - 0 for unlimited capture
*/
...
...
@@ -827,7 +827,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
/*
MAV_CMD_VIDEO_START_CAPTURE WIP: Starts video capture (recording)
Mission Param #1
Camera ID (0 for all cameras, 1 for first, 2 for second, etc.
)
Mission Param #1
Reserved (Set to 0
)
Mission Param #2 Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise frequency in Hz)
Mission Param #3 Reserved
*/
...
...
@@ -845,7 +845,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
// Start Video command but incorrect settings
SimpleMissionItem
invalidSimpleItem
(
_offlineVehicle
,
_validStartVideoItem
->
missionItem
());
invalidSimpleItem
.
missionItem
().
setParam1
(
10
);
//
Camera id must be 0
invalidSimpleItem
.
missionItem
().
setParam1
(
10
);
//
Reserved (must be 0)
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
visualItems
.
count
(),
1
);
...
...
@@ -872,7 +872,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
/*
MAV_CMD_VIDEO_STOP_CAPTURE Stop the current video capture (recording)
Mission Param #1
WIP: Camera ID
Mission Param #1
Reserved (Set to 0)
*/
SimpleMissionItem
*
newValidStopVideoItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
this
);
...
...
@@ -942,7 +942,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
/*
MAV_CMD_IMAGE_START_CAPTURE WIP: Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture.
Mission Param #1
Camera ID (0 for all cameras, 1 for first, 2 for second, etc.
)
Mission Param #1
Reserved (Set to 0
)
Mission Param #2 Duration between two consecutive pictures (in seconds)
Mission Param #3 Number of images to capture total - 0 for unlimited capture
Mission Param #4 Reserved
...
...
src/MissionManager/MavCmdInfoCommon.json
View file @
25d43fd7
...
...
@@ -974,7 +974,7 @@
"description"
:
"Set camera photo, video, audio modes."
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"
Camera i
d"
,
"label"
:
"
Rserve
d"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
...
...
@@ -992,7 +992,7 @@
"description"
:
"Start taking one or more photos."
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"
Camera i
d"
,
"label"
:
"
Rserve
d"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
...
...
@@ -1015,7 +1015,7 @@
"description"
:
"Stop taking photos."
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"
Camera i
d"
,
"label"
:
"
Rserve
d"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
...
...
@@ -1028,7 +1028,7 @@
"description"
:
"Start video capture."
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"
Camera i
d"
,
"label"
:
"
Rserve
d"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
...
...
@@ -1040,7 +1040,7 @@
"description"
:
"Stop video capture."
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"
Camera i
d"
,
"label"
:
"
Rserve
d"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
...
...
src/MissionManager/SurveyMissionItem.cc
View file @
25d43fd7
...
...
@@ -1150,7 +1150,7 @@ int SurveyMissionItem::_appendWaypointToMission(QList<MissionItem*>& items, int
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_IMAGE_START_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
//
Camera ID, all cameras
0
,
//
Reserved (Set to 0)
0
,
// Interval (none)
1
,
// Take 1 photo
NAN
,
NAN
,
NAN
,
NAN
,
// param 4-7 reserved
...
...
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