Commit f846055e authored by DonLakeFlyer's avatar DonLakeFlyer

Camera Feedback on Fly View

parent 0be3b970
......@@ -46,6 +46,7 @@
<file alias="Airframe/HelicopterCoaxial">src/AutoPilotPlugins/Common/Images/HelicopterCoaxial.svg</file>
<file alias="wifi.svg">src/AutoPilotPlugins/Common/Images/wifi.svg</file>
<file alias="arrow-down.png">src/QmlControls/arrow-down.png</file>
<file alias="camera.svg">resources/camera.svg</file>
<file alias="check.png">src/QmlControls/check.png</file>
<file alias="FirmwareUpgradeIcon.png">src/VehicleSetup/FirmwareUpgradeIcon.png</file>
<file alias="FlightModesComponentIcon.png">src/AutoPilotPlugins/PX4/Images/FlightModesComponentIcon.png</file>
......
......@@ -135,6 +135,7 @@
<file alias="QGroundControl/FlightDisplay/GuidedAltitudeSlider.qml">src/FlightDisplay/GuidedAltitudeSlider.qml</file>
<file alias="QGroundControl/FlightDisplay/MultiVehicleList.qml">src/FlightDisplay/MultiVehicleList.qml</file>
<file alias="QGroundControl/FlightDisplay/qmldir">src/FlightDisplay/qmldir</file>
<file alias="QGroundControl/FlightMap/CameraTriggerIndicator.qml">src/FlightMap/MapItems/CameraTriggerIndicator.qml</file>
<file alias="QGroundControl/FlightMap/CenterMapDropButton.qml">src/FlightMap/Widgets/CenterMapDropButton.qml</file>
<file alias="QGroundControl/FlightMap/CenterMapDropPanel.qml">src/FlightMap/Widgets/CenterMapDropPanel.qml</file>
<file alias="QGroundControl/FlightMap/CompassRing.qml">src/FlightMap/Widgets/CompassRing.qml</file>
......
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 21.0.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 72 72" style="enable-background:new 0 0 72 72;" xml:space="preserve">
<style type="text/css">
.st0{fill:#FFFFFF;}
</style>
<g>
<path class="st0" d="M25.758,41.569c0,5.672,4.592,10.264,10.264,10.264s10.264-4.592,10.264-10.264s-4.592-10.264-10.264-10.264
C30.35,31.305,25.758,35.897,25.758,41.569z"/>
<path class="st0" d="M55.477,20.513l-0.47-4.438c-0.228-2.16-1.22-4.188-2.961-5.753s-3.923-2.278-6.091-2.278H25.92
c-2.175,0-4.349,0.749-6.091,2.314c-1.741,1.572-2.733,3.563-2.961,5.723l-0.47,4.43H9.162c-2.329,0-4.687,0.97-6.465,2.748
C0.918,25.038,0,27.448,0,29.777v24.818c0,2.329,0.918,4.79,2.696,6.561s4.136,2.799,6.465,2.799h53.706
c2.329,0,4.673-1.021,6.451-2.792C71.096,59.385,72,56.931,72,54.602V29.777c0-2.329-0.904-4.739-2.682-6.517
s-4.122-2.748-6.451-2.748L55.477,20.513L55.477,20.513z M36.022,59.062c-9.661,0-17.493-7.832-17.493-17.493
s7.832-17.493,17.493-17.493s17.493,7.832,17.493,17.493S45.683,59.062,36.022,59.062z M59.018,34.082
c-1.918,0-3.475-1.558-3.475-3.475s1.558-3.475,3.475-3.475s3.475,1.558,3.475,3.475C62.493,32.525,60.936,34.082,59.018,34.082z"
/>
</g>
</svg>
......@@ -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
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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"
}
}
}
......@@ -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
......
......@@ -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();
}
......@@ -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;
......
......@@ -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;
}
}
......
......@@ -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);
......
......@@ -9,11 +9,13 @@
#include "QGCQGeoCoordinate.h"
#include <QQmlEngine>
QGCQGeoCoordinate::QGCQGeoCoordinate(const QGeoCoordinate& coord, QObject* parent)
: QObject(parent)
, _coordinate(coord)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
}
void QGCQGeoCoordinate::setCoordinate(const QGeoCoordinate& coordinate)
......
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