Commit dd2ab8d8 authored by DonLakeFlyer's avatar DonLakeFlyer

Move camera trigger points to Vehicle

parent e66ae88b
......@@ -245,9 +245,9 @@ FlightMap {
}
}
// Camera points
// Camera trigger points
MapItemView {
model: _missionController.cameraPoints
model: _activeVehicle ? _activeVehicle.cameraTriggerPoints : 0
delegate: CameraTriggerIndicator {
coordinate: object.coordinate
......
......@@ -1384,7 +1384,6 @@ void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
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(_managerVehicle, &Vehicle::homePositionChanged, this, &MissionController::_managerVehicleHomePositionChanged);
connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged, this, &MissionController::_recalcMissionFlightStatus);
......@@ -1664,19 +1663,6 @@ void MissionController::applyDefaultMissionAltitude(void)
}
}
void MissionController::_cameraFeedback(QGeoCoordinate imageCoordinate, int index)
{
Q_UNUSED(index);
if (!_editMode) {
_cameraPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
}
}
void MissionController::clearCameraPoints(void)
{
_cameraPoints.clearAndDeleteContents();
}
void MissionController::_progressPctChanged(double progressPct)
{
if (!qFuzzyCompare(progressPct, _progressPct)) {
......
......@@ -64,7 +64,6 @@ 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)
......@@ -106,8 +105,6 @@ public:
/// Sends the mission items to the specified vehicle
static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems);
Q_INVOKABLE void clearCameraPoints(void);
bool loadJsonFile(QFile& file, QString& errorString);
bool loadTextFile(QFile& file, QString& errorString);
......@@ -130,7 +127,6 @@ public:
QmlObjectListModel* visualItems (void) { return _visualItems; }
QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
QmlObjectListModel* cameraPoints (void) { return &_cameraPoints; }
QStringList complexMissionItemNames (void) const;
QGeoCoordinate plannedHomePosition (void) const;
double progressPct (void) const { return _progressPct; }
......@@ -178,7 +174,6 @@ private slots:
void _recalcWaypointLines(void);
void _recalcMissionFlightStatus(void);
void _updateContainsItems(void);
void _cameraFeedback(QGeoCoordinate imageCoordinate, int index);
void _progressPctChanged(double progressPct);
void _visualItemsDirtyChanged(bool dirty);
void _managerSendComplete(void);
......@@ -220,7 +215,6 @@ private:
QmlObjectListModel* _visualItems;
MissionSettingsItem* _settingsItem;
QmlObjectListModel _waypointLines;
QmlObjectListModel _cameraPoints;
CoordVectHashTable _linesTable;
bool _firstItemsFromVehicle;
bool _itemsRequested;
......
......@@ -680,31 +680,6 @@ void MissionManager::_handleMissionAck(const mavlink_message_t& message)
break;
}
}
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)
{
......@@ -740,14 +715,6 @@ 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;
}
}
......
......@@ -88,7 +88,6 @@ signals:
void currentIndexChanged(int currentIndex);
void lastCurrentIndexChanged(int lastCurrentIndex);
void resumeMissionReady(void);
void cameraFeedback(QGeoCoordinate imageCoordinate, int index);
void progressPct(double progressPercentPct);
void removeAllComplete (void);
void sendComplete (void);
......@@ -122,8 +121,6 @@ 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);
......
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