diff --git a/qgcresources.qrc b/qgcresources.qrc
index ceb5b84449fc5ccf784f17186b93e8d84a888246..ab45927ff935a07ce0046e67ef6211f677c9e1cc 100644
--- a/qgcresources.qrc
+++ b/qgcresources.qrc
@@ -46,6 +46,7 @@
src/AutoPilotPlugins/Common/Images/HelicopterCoaxial.svg
src/AutoPilotPlugins/Common/Images/wifi.svg
src/QmlControls/arrow-down.png
+ resources/camera.svg
src/QmlControls/check.png
src/VehicleSetup/FirmwareUpgradeIcon.png
src/AutoPilotPlugins/PX4/Images/FlightModesComponentIcon.png
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 62267c300b3111862fea1c8f27fb3d6131b09c8e..4e9f6343d8bebc0786e3872521de3d69df520fe2 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -135,6 +135,7 @@
src/FlightDisplay/GuidedAltitudeSlider.qml
src/FlightDisplay/MultiVehicleList.qml
src/FlightDisplay/qmldir
+ src/FlightMap/MapItems/CameraTriggerIndicator.qml
src/FlightMap/Widgets/CenterMapDropButton.qml
src/FlightMap/Widgets/CenterMapDropPanel.qml
src/FlightMap/Widgets/CompassRing.qml
diff --git a/resources/camera.svg b/resources/camera.svg
new file mode 100644
index 0000000000000000000000000000000000000000..5a640fb993d9371e4658050c01e8f58b772c3f49
--- /dev/null
+++ b/resources/camera.svg
@@ -0,0 +1,20 @@
+
+
+
diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml
index 7e5a9911e784d8d8cffdb2174b9bb85e6b6d3554..1ccd3ae4dd37b10caa214d38188420029409d172 100644
--- a/src/FlightDisplay/FlightDisplayViewMap.qml
+++ b/src/FlightDisplay/FlightDisplayViewMap.qml
@@ -241,6 +241,16 @@ FlightMap {
}
}
+ // Camera points
+ MapItemView {
+ model: missionController.cameraPoints
+
+ delegate: CameraTriggerIndicator {
+ coordinate: object.coordinate
+ z: QGroundControl.zOrderTopMost
+ }
+ }
+
// Handle guided mode clicks
MouseArea {
anchors.fill: parent
diff --git a/src/FlightMap/MapItems/CameraTriggerIndicator.qml b/src/FlightMap/MapItems/CameraTriggerIndicator.qml
new file mode 100644
index 0000000000000000000000000000000000000000..124808d8ac1be63b65979e191fad56c926862f0a
--- /dev/null
+++ b/src/FlightMap/MapItems/CameraTriggerIndicator.qml
@@ -0,0 +1,41 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+import QtQuick 2.3
+import QtLocation 5.3
+import QtQuick.Controls 1.2
+
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.Controls 1.0
+import QGroundControl.Vehicle 1.0
+
+/// Marker for displaying a camera trigger on the map
+MapQuickItem {
+ anchorPoint.x: sourceItem.width / 2
+ anchorPoint.y: sourceItem.height / 2
+
+ sourceItem: Rectangle {
+ width: _radius * 2
+ height: _radius * 2
+ radius: _radius
+ color: "black"
+ opacity: 0.4
+
+ readonly property real _radius: ScreenTools.defaultFontPixelHeight * 0.6
+
+ QGCColoredImage {
+ anchors.margins: 3
+ anchors.fill: parent
+ color: "white"
+ mipmap: true
+ fillMode: Image.PreserveAspectFit
+ source: "/qmlimages/camera.svg"
+ }
+ }
+}
diff --git a/src/FlightMap/qmldir b/src/FlightMap/qmldir
index b507ba25e5361b2a15e6e8dae2153e0620ede032..9afe7d25f264f96ba86619235822be5661b9a941 100644
--- a/src/FlightMap/qmldir
+++ b/src/FlightMap/qmldir
@@ -22,6 +22,7 @@ VehicleHealthWidget 1.0 VehicleHealthWidget.qml
VibrationWidget 1.0 VibrationWidget.qml
# Map items
+CameraTriggerIndicator 1.0 CameraTriggerIndicator.qml
MissionItemIndicator 1.0 MissionItemIndicator.qml
MissionItemIndicatorDrag 1.0 MissionItemIndicatorDrag.qml
MissionItemView 1.0 MissionItemView.qml
diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc
index df7d6ca78eb6096f1d592ea833cf38630e6c4f8a..f14d72d8250b84439a7299d1d34cb642ad67b294 100644
--- a/src/MissionManager/MissionController.cc
+++ b/src/MissionManager/MissionController.cc
@@ -23,6 +23,7 @@
#include "SettingsManager.h"
#include "AppSettings.h"
#include "MissionSettingsItem.h"
+#include "QGCQGeoCoordinate.h"
#ifndef __mobile__
#include "MainWindow.h"
@@ -1330,6 +1331,7 @@ void MissionController::_activeVehicleBeingRemoved(void)
disconnect(missionManager, &MissionManager::currentIndexChanged, this, &MissionController::_currentMissionIndexChanged);
disconnect(missionManager, &MissionManager::lastCurrentIndexChanged, this, &MissionController::resumeMissionIndexChanged);
disconnect(missionManager, &MissionManager::resumeMissionReady, this, &MissionController::resumeMissionReady);
+ disconnect(missionManager, &MissionManager::cameraFeedback, this, &MissionController::_cameraFeedback);
disconnect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged);
// We always remove all items on vehicle change. This leaves a user model hole:
@@ -1350,6 +1352,7 @@ void MissionController::_activeVehicleSet(void)
connect(missionManager, &MissionManager::currentIndexChanged, this, &MissionController::_currentMissionIndexChanged);
connect(missionManager, &MissionManager::lastCurrentIndexChanged, this, &MissionController::resumeMissionIndexChanged);
connect(missionManager, &MissionManager::resumeMissionReady, this, &MissionController::resumeMissionReady);
+ connect(missionManager, &MissionManager::cameraFeedback, this, &MissionController::_cameraFeedback);
connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged);
connect(_activeVehicle, &Vehicle::defaultCruiseSpeedChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(_activeVehicle, &Vehicle::defaultHoverSpeedChanged, this, &MissionController::_recalcMissionFlightStatus);
@@ -1614,3 +1617,16 @@ void MissionController::applyDefaultMissionAltitude(void)
item->applyNewAltitude(defaultAltitude);
}
}
+
+void MissionController::_cameraFeedback(QGeoCoordinate imageCoordinate, int index)
+{
+ Q_UNUSED(index);
+ if (!_editMode) {
+ _cameraPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
+ }
+}
+
+void MissionController::clearCameraPoints(void)
+{
+ _cameraPoints.clearAndDeleteContents();
+}
diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h
index 125bbe3fdd472998845976780d94811499081722..a0aa71d559c8a2aed0292278fcc6a4e27232122e 100644
--- a/src/MissionManager/MissionController.h
+++ b/src/MissionManager/MissionController.h
@@ -62,6 +62,7 @@ public:
Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
+ Q_PROPERTY(QmlObjectListModel* cameraPoints READ cameraPoints CONSTANT)
Q_PROPERTY(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged)
Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
@@ -107,6 +108,8 @@ public:
/// Sends the mission items to the specified vehicle
static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems);
+ Q_INVOKABLE void clearCameraPoints(void);
+
// Overrides from PlanElementController
void start (bool editMode) final;
void startStaticActiveVehicle (Vehicle* vehicle) final;
@@ -127,6 +130,7 @@ public:
QmlObjectListModel* visualItems (void) { return _visualItems; }
QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
+ QmlObjectListModel* cameraPoints (void) { return &_cameraPoints; }
QStringList complexMissionItemNames (void) const;
QGeoCoordinate plannedHomePosition (void) const;
@@ -171,6 +175,7 @@ private slots:
void _recalcWaypointLines(void);
void _recalcMissionFlightStatus(void);
void _updateContainsItems(void);
+ void _cameraFeedback(QGeoCoordinate imageCoordinate, int index);
private:
void _init(void);
@@ -209,6 +214,7 @@ private:
QmlObjectListModel* _visualItems;
MissionSettingsItem* _settingsItem;
QmlObjectListModel _waypointLines;
+ QmlObjectListModel _cameraPoints;
CoordVectHashTable _linesTable;
bool _firstItemsFromVehicle;
bool _missionItemsRequested;
diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc
index 9f85c02980684c63e778b19e1d80a86a8915f954..358b1c7d2a0479308d413359723d990339838eeb 100644
--- a/src/MissionManager/MissionManager.cc
+++ b/src/MissionManager/MissionManager.cc
@@ -666,6 +666,30 @@ void MissionManager::_handleMissionAck(const mavlink_message_t& message)
}
}
+void MissionManager::_handleCameraFeedback(const mavlink_message_t& message)
+{
+ mavlink_camera_feedback_t feedback;
+
+ mavlink_msg_camera_feedback_decode(&message, &feedback);
+
+ QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lng / qPow(10.0, 7.0), feedback.alt_msl);
+ qCDebug(MissionManagerLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.img_idx;
+ emit cameraFeedback(imageCoordinate, feedback.img_idx);
+}
+
+void MissionManager::_handleCameraImageCaptured(const mavlink_message_t& message)
+{
+ mavlink_camera_image_captured_t feedback;
+
+ mavlink_msg_camera_image_captured_decode(&message, &feedback);
+
+ QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lon / qPow(10.0, 7.0), feedback.alt);
+ qCDebug(MissionManagerLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.image_index << feedback.capture_result;
+ if (feedback.capture_result == 1) {
+ emit cameraFeedback(imageCoordinate, feedback.image_index);
+ }
+}
+
/// Called when a new mavlink message for out vehicle is received
void MissionManager::_mavlinkMessageReceived(const mavlink_message_t& message)
{
@@ -701,6 +725,14 @@ void MissionManager::_mavlinkMessageReceived(const mavlink_message_t& message)
case MAVLINK_MSG_ID_MISSION_CURRENT:
_handleMissionCurrent(message);
break;
+
+ case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
+ _handleCameraFeedback(message);
+ break;
+
+ case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
+ _handleCameraImageCaptured(message);
+ break;
}
}
diff --git a/src/MissionManager/MissionManager.h b/src/MissionManager/MissionManager.h
index 9a235cfd6b1f9712f16957a877c5f7e0101028b9..b15ad967e9b06aa898ac15718c9b7734033b6498 100644
--- a/src/MissionManager/MissionManager.h
+++ b/src/MissionManager/MissionManager.h
@@ -84,6 +84,7 @@ signals:
void currentIndexChanged(int currentIndex);
void lastCurrentIndexChanged(int lastCurrentIndex);
void resumeMissionReady(void);
+ void cameraFeedback(QGeoCoordinate imageCoordinate, int index);
private slots:
void _mavlinkMessageReceived(const mavlink_message_t& message);
@@ -114,6 +115,8 @@ private:
void _handleMissionRequest(const mavlink_message_t& message, bool missionItemInt);
void _handleMissionAck(const mavlink_message_t& message);
void _handleMissionCurrent(const mavlink_message_t& message);
+ void _handleCameraFeedback(const mavlink_message_t& message);
+ void _handleCameraImageCaptured(const mavlink_message_t& message);
void _requestNextMissionItem(void);
void _clearMissionItems(void);
void _sendError(ErrorCode_t errorCode, const QString& errorMsg);
diff --git a/src/QGCQGeoCoordinate.cc b/src/QGCQGeoCoordinate.cc
index c19e2af10f08303594c64d2f17f8e838e83dacb0..90bb9ae4c530551fd693b290dddbde6def245d49 100644
--- a/src/QGCQGeoCoordinate.cc
+++ b/src/QGCQGeoCoordinate.cc
@@ -9,11 +9,13 @@
#include "QGCQGeoCoordinate.h"
+#include
+
QGCQGeoCoordinate::QGCQGeoCoordinate(const QGeoCoordinate& coord, QObject* parent)
: QObject(parent)
, _coordinate(coord)
{
-
+ QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
}
void QGCQGeoCoordinate::setCoordinate(const QGeoCoordinate& coordinate)