Commit 62d7bd4c authored by DonLakeFlyer's avatar DonLakeFlyer

Show gimbal yaw on map

parent fbc34cc5
......@@ -29,10 +29,13 @@ MapQuickItem {
sourceItem:
MissionItemIndexLabel {
id: _label
checked: _isCurrentItem
label: missionItem ? missionItem.abbreviation : ""
onClicked: _item.clicked()
id: _label
checked: _isCurrentItem
label: missionItem ? missionItem.abbreviation : ""
gimbalYaw: missionItem.missionGimbalYaw
vehicleYaw: missionItem.missionVehicleYaw
showGimbalYaw: missionItem.showMissionGimbalYaw
onClicked: _item.clicked()
property bool _isCurrentItem: missionItem ? missionItem.isCurrentItem : false
}
......
......@@ -115,9 +115,9 @@ Item {
model: _missionItem.childItems
delegate: MissionItemIndexLabel {
z: 2
label: object.abbreviation
checked: object.isCurrentItem
z: 2
specifiesCoordinate: false
onClicked: setCurrentItem(object.sequenceNumber)
......
......@@ -55,6 +55,8 @@ CameraSection::CameraSection(QObject* parent)
connect(&_gimbalYawFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
connect(&_cameraPhotoIntervalDistanceFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
connect(&_cameraPhotoIntervalTimeFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
connect(&_gimbalYawFact, &Fact::valueChanged, this, &CameraSection::_updateSpecifiedGimbalYaw);
}
void CameraSection::setSpecifyGimbal(bool specifyGimbal)
......@@ -254,3 +256,13 @@ void CameraSection::setAvailable(bool available)
emit availableChanged(available);
}
}
double CameraSection::specifiedGimbalYaw(void) const
{
return _specifyGimbal ? _gimbalYawFact.rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
}
void CameraSection::_updateSpecifiedGimbalYaw(void)
{
emit specifiedGimbalYawChanged(specifiedGimbalYaw());
}
......@@ -49,6 +49,9 @@ public:
Fact* cameraPhotoIntervalTime (void) { return &_cameraPhotoIntervalTimeFact; }
Fact* cameraPhotoIntervalDistance (void) { return &_cameraPhotoIntervalDistanceFact; }
///< @return The gimbal yaw specified by this item, NaN if not specified
double specifiedGimbalYaw(void) const;
/// Scans the loaded items for the section items
/// @param visualItems Item list
/// @param scanIndex Index to start scanning from
......@@ -75,10 +78,12 @@ signals:
void dirtyChanged (bool dirty);
bool specifyGimbalChanged (bool specifyGimbal);
void missionItemCountChanged (int missionItemCount);
void specifiedGimbalYawChanged (double gimbalYaw);
private slots:
void _setDirty(void);
void _setDirtyAndUpdateMissionItemCount(void);
void _updateSpecifiedGimbalYaw(void);
private:
bool _available;
......
......@@ -38,9 +38,6 @@ public:
/// @return the greatest distance from any point of the complex item to some coordinate
virtual double greatestDistanceTo(const QGeoCoordinate &other) const = 0;
/// Informs the complex item of the cruise speed it will fly at
virtual void setCruiseSpeed(double cruiseSpeed) = 0;
/// This mission item attribute specifies the type of the complex item.
static const char* jsonComplexItemTypeKey;
......
......@@ -250,12 +250,6 @@ double FixedWingLandingComplexItem::complexDistance(void) const
return _loiterCoordinate.distanceTo(_landingCoordinate);
}
void FixedWingLandingComplexItem::setCruiseSpeed(double cruiseSpeed)
{
// We don't care about cruise speed
Q_UNUSED(cruiseSpeed);
}
void FixedWingLandingComplexItem::setLandingCoordinate(const QGeoCoordinate& coordinate)
{
if (coordinate != _landingCoordinate) {
......
......@@ -55,7 +55,6 @@ public:
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
double greatestDistanceTo (const QGeoCoordinate &other) const final;
void setCruiseSpeed (double cruiseSpeed) final;
QString mapVisualQML (void) const final { return QStringLiteral("FWLandingPatternMapVisual.qml"); }
// Overrides from VisualMissionItem
......@@ -71,7 +70,8 @@ public:
QGeoCoordinate coordinate (void) const final { return _loiterCoordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _landingCoordinate; }
int sequenceNumber (void) const final { return _sequenceNumber; }
double flightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedFlightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
bool coordinateHasRelativeAltitude (void) const final { return true; }
......
......@@ -52,14 +52,18 @@ MissionController::MissionController(QObject *parent)
, _firstItemsFromVehicle(false)
, _missionItemsRequested(false)
, _queuedSend(false)
, _missionDistance(0.0)
, _missionTime(0.0)
, _missionHoverDistance(0.0)
, _missionHoverTime(0.0)
, _missionCruiseDistance(0.0)
, _missionCruiseTime(0.0)
, _missionMaxTelemetry(0.0)
{
_missionFlightStatus.maxTelemetryDistance = 0;
_missionFlightStatus.totalDistance = 0;
_missionFlightStatus.totalTime = 0;
_missionFlightStatus.hoverDistance = 0;
_missionFlightStatus.hoverTime = 0;
_missionFlightStatus.cruiseDistance = 0;
_missionFlightStatus.cruiseTime = 0;
_missionFlightStatus.cruiseSpeed = 0;
_missionFlightStatus.hoverSpeed = 0;
_missionFlightStatus.gimbalYaw = 0;
_surveyMissionItemName = tr("Survey");
_fwLandingMissionItemName = tr("Fixed Wing Landing");
_complexMissionItemNames << _surveyMissionItemName << _fwLandingMissionItemName;
......@@ -475,23 +479,23 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje
qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
visualItems->append(surveyItem);
} else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(vehicle, visualItems);
if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
visualItems->append(landingItem);
qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(vehicle, visualItems);
if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
visualItems->append(landingItem);
} else if (complexItemType == MissionSettingsComplexItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
if (!settingsItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
nextSequenceNumber = settingsItem->lastSequenceNumber() + 1;
qCDebug(MissionControllerLog) << "Mission Settings load complete: nextSequenceNumber" << nextSequenceNumber;
visualItems->append(settingsItem);
qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
if (!settingsItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
nextSequenceNumber = settingsItem->lastSequenceNumber() + 1;
qCDebug(MissionControllerLog) << "Mission Settings load complete: nextSequenceNumber" << nextSequenceNumber;
visualItems->append(settingsItem);
} else {
errorString = tr("Unsupported complex item type: %1").arg(complexItemType);
}
......@@ -689,8 +693,8 @@ void MissionController::saveToFile(const QString& filename)
missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->cruiseSpeed();
missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->hoverSpeed();
missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->defaultCruiseSpeed();
missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->defaultHoverSpeed();
// Save the visual items
QJsonArray rgMissionItems;
......@@ -816,7 +820,7 @@ void MissionController::_recalcWaypointLines(void)
// FIXME: We should ideally have signals for 2D position change, alt change, and 3D position change
// Not optimal, but still pretty fast, do a full update of range/bearing/altitudes
connect(item, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcAltitudeRangeBearing);
connect(item, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
_linesTable[pair] = linevect;
}
}
......@@ -840,12 +844,12 @@ void MissionController::_recalcWaypointLines(void)
// Anything left in the old table is an obsolete line object that can go
qDeleteAll(old_table);
_recalcAltitudeRangeBearing();
_recalcMissionFlightStatus();
emit waypointLinesChanged();
}
void MissionController::_recalcAltitudeRangeBearing()
void MissionController::_recalcMissionFlightStatus()
{
if (!_visualItems->count()) {
return;
......@@ -861,7 +865,7 @@ void MissionController::_recalcAltitudeRangeBearing()
bool showHomePosition = settingsItem->showHomePosition();
qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing";
qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
// If home position is valid we can calculate distances between all waypoints.
// If home position is not valid we can only calculate distances between waypoints which are
......@@ -877,22 +881,24 @@ void MissionController::_recalcAltitudeRangeBearing()
const double homePositionAltitude = settingsItem->coordinate().altitude();
minAltSeen = maxAltSeen = settingsItem->coordinate().altitude();
double missionDistance = 0.0;
double missionMaxTelemetry = 0.0;
double missionTime = 0.0;
double vtolHoverTime = 0.0;
double vtolCruiseTime = 0.0;
double vtolHoverDistance = 0.0;
double vtolCruiseDistance = 0.0;
double currentCruiseSpeed = _activeVehicle->cruiseSpeed();
double currentHoverSpeed = _activeVehicle->hoverSpeed();
bool vtolVehicle = _activeVehicle->vtol();
bool vtolInHover = true;
double lastVehicleYaw = 0;
_missionFlightStatus.totalDistance = 0.0;
_missionFlightStatus.maxTelemetryDistance = 0.0;
_missionFlightStatus.totalTime = 0.0;
_missionFlightStatus.hoverTime = 0.0;
_missionFlightStatus.cruiseTime = 0.0;
_missionFlightStatus.hoverDistance = 0.0;
_missionFlightStatus.cruiseDistance = 0.0;
_missionFlightStatus.cruiseSpeed = _activeVehicle->defaultCruiseSpeed();
_missionFlightStatus.hoverSpeed = _activeVehicle->defaultHoverSpeed();
_missionFlightStatus.vehicleSpeed = _activeVehicle->multiRotor() || _activeVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
_missionFlightStatus.gimbalYaw = std::numeric_limits<double>::quiet_NaN();
bool vtolInHover = true;
bool linkBackToHome = false;
for (int i=1; i<_visualItems->count(); i++) {
for (int i=0; i<_visualItems->count(); i++) {
VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
......@@ -901,16 +907,32 @@ void MissionController::_recalcAltitudeRangeBearing()
item->setAzimuth(0.0);
item->setDistance(0.0);
if (simpleItem && simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_DO_CHANGE_SPEED) {
// Adjust cruise speed for time calculations
double newSpeed = simpleItem->missionItem().param2();
if (newSpeed > 0) {
if (_activeVehicle->multiRotor()) {
currentHoverSpeed = newSpeed;
// Look for speed changed
double newSpeed = item->specifiedFlightSpeed();
if (!qIsNaN(newSpeed)) {
if (_activeVehicle->multiRotor()) {
_missionFlightStatus.hoverSpeed = newSpeed;
} else if (_activeVehicle->vtol()) {
if (vtolInHover) {
_missionFlightStatus.hoverSpeed = newSpeed;
} else {
currentCruiseSpeed = newSpeed;
_missionFlightStatus.cruiseSpeed = newSpeed;
}
} else {
_missionFlightStatus.cruiseSpeed = newSpeed;
}
_missionFlightStatus.vehicleSpeed = newSpeed;
}
// Look for gimbal change
double gimbalYaw = item->specifiedGimbalYaw();
if (!qIsNaN(gimbalYaw)) {
_missionFlightStatus.gimbalYaw = gimbalYaw;
}
if (i == 0) {
// We only process speed and gimbal from Mission Settings item
continue;
}
// Link back to home if first item is takeoff and we have home position
......@@ -921,7 +943,7 @@ void MissionController::_recalcAltitudeRangeBearing()
}
// Update VTOL state
if (simpleItem && vtolVehicle) {
if (simpleItem && _activeVehicle->vtol()) {
switch (simpleItem->command()) {
case MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF:
vtolInHover = false;
......@@ -945,6 +967,12 @@ void MissionController::_recalcAltitudeRangeBearing()
}
if (item->specifiesCoordinate()) {
// Update vehicle yaw assuming direction to next waypoint
if (item != lastCoordinateItem) {
lastVehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
lastCoordinateItem->setMissionVehicleYaw(lastVehicleYaw);
}
// Keep track of the min/max altitude for all waypoints so we can show altitudes as a percentage
double absoluteAltitude = item->coordinate().altitude();
......@@ -974,51 +1002,84 @@ void MissionController::_recalcAltitudeRangeBearing()
item->setAzimuth(azimuth);
item->setDistance(distance);
missionDistance += distance;
missionMaxTelemetry = qMax(missionMaxTelemetry, _calcDistanceToHome(item, settingsItem));
_missionFlightStatus.totalDistance += distance;
_missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, settingsItem));
// Calculate mission time
if (vtolVehicle) {
// Calculate time/distance
double hoverTime = distance / _missionFlightStatus.hoverSpeed;
double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
if (_activeVehicle->vtol()) {
if (vtolInHover) {
double hoverTime = distance / _activeVehicle->hoverSpeed();
missionTime += hoverTime;
vtolHoverTime += hoverTime;
vtolHoverDistance += distance;
_missionFlightStatus.totalTime += hoverTime;
_missionFlightStatus.hoverTime += hoverTime;
_missionFlightStatus.hoverDistance += distance;
} else {
double cruiseTime = distance / currentCruiseSpeed;
missionTime += cruiseTime;
vtolCruiseTime += cruiseTime;
vtolCruiseDistance += distance;
_missionFlightStatus.totalTime += cruiseTime;
_missionFlightStatus.cruiseTime += cruiseTime;
_missionFlightStatus.cruiseDistance += distance;
}
} else {
missionTime += distance / (_activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed);
if (_activeVehicle->multiRotor()) {
_missionFlightStatus.totalTime += hoverTime;
_missionFlightStatus.hoverTime += hoverTime;
_missionFlightStatus.hoverDistance += distance;
} else {
_missionFlightStatus.totalTime += cruiseTime;
_missionFlightStatus.cruiseTime += cruiseTime;
_missionFlightStatus.cruiseDistance += distance;
}
}
}
if (complexItem) {
// Add in distance/time inside survey as well
// This code assumes all surveys are done cruise not hover
double complexDistance = complexItem->complexDistance();
double cruiseSpeed = _activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed;
missionDistance += complexDistance;
missionTime += complexDistance / cruiseSpeed;
missionMaxTelemetry = qMax(missionMaxTelemetry, complexItem->greatestDistanceTo(settingsItem->exitCoordinate()));
// Let the complex item know the current cruise speed
complexItem->setCruiseSpeed(cruiseSpeed);
// Add in distance/time inside complex items as well
double distance = complexItem->complexDistance();
_missionFlightStatus.totalDistance += distance;
_missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(settingsItem->exitCoordinate()));
double hoverTime = _missionFlightStatus.totalDistance / _missionFlightStatus.hoverSpeed;
double cruiseTime = _missionFlightStatus.totalDistance / _missionFlightStatus.cruiseSpeed;
if (_activeVehicle->vtol()) {
if (vtolInHover) {
_missionFlightStatus.totalTime += hoverTime;
_missionFlightStatus.hoverTime += hoverTime;
_missionFlightStatus.hoverDistance += distance;
} else {
_missionFlightStatus.totalTime += cruiseTime;
_missionFlightStatus.cruiseTime += cruiseTime;
_missionFlightStatus.cruiseDistance += distance;
}
} else {
if (_activeVehicle->multiRotor()) {
_missionFlightStatus.totalTime += hoverTime;
_missionFlightStatus.hoverTime += hoverTime;
_missionFlightStatus.hoverDistance += distance;
} else {
_missionFlightStatus.totalTime += cruiseTime;
_missionFlightStatus.cruiseTime += cruiseTime;
_missionFlightStatus.cruiseDistance += distance;
}
}
}
item->setMissionFlightStatus(_missionFlightStatus);
}
lastCoordinateItem = item;
}
}
lastCoordinateItem->setMissionVehicleYaw(lastVehicleYaw);
_setMissionMaxTelemetry(missionMaxTelemetry);
_setMissionDistance(missionDistance);
_setMissionTime(missionTime);
_setMissionHoverDistance(vtolHoverDistance);
_setMissionHoverTime(vtolHoverTime);
_setMissionCruiseDistance(vtolCruiseDistance);
_setMissionCruiseTime(vtolCruiseTime);
emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
emit missionDistanceChanged(_missionFlightStatus.totalDistance);
emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
emit missionTimeChanged();
emit missionHoverTimeChanged();
emit missionCruiseTimeChanged();
// Walk the list again calculating altitude percentages
double altRange = maxAltSeen - minAltSeen;
......@@ -1135,7 +1196,8 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged, this, &MissionController::_recalcWaypointLines);
connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged, this, &MissionController::_recalcWaypointLines);
connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged, this, &MissionController::_recalcWaypointLines);
connect(visualItem, &VisualMissionItem::flightSpeedChanged, this, &MissionController::_recalcAltitudeRangeBearing);
connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence);
if (visualItem->isSimpleItem()) {
......@@ -1149,7 +1211,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
} else {
ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
if (complexItem) {
connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcAltitudeRangeBearing);
connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
} else {
qWarning() << "ComplexMissionItem not found";
}
......@@ -1198,8 +1260,8 @@ void MissionController::_activeVehicleSet(void)
connect(missionManager, &MissionManager::currentItemChanged, this, &MissionController::_currentMissionItemChanged);
connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged);
connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged);
connect(_activeVehicle, &Vehicle::cruiseSpeedChanged, this, &MissionController::_recalcAltitudeRangeBearing);
connect(_activeVehicle, &Vehicle::hoverSpeedChanged, this, &MissionController::_recalcAltitudeRangeBearing);
connect(_activeVehicle, &Vehicle::defaultCruiseSpeedChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(_activeVehicle, &Vehicle::defaultHoverSpeedChanged, this, &MissionController::_recalcMissionFlightStatus);
if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
// We are switching between two previously existing vehicles. We have to manually ask for the items from the Vehicle.
......@@ -1246,57 +1308,57 @@ void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate&
void MissionController::_setMissionMaxTelemetry(double missionMaxTelemetry)
{
if (!qFuzzyCompare(_missionMaxTelemetry, missionMaxTelemetry)) {
_missionMaxTelemetry = missionMaxTelemetry;
emit missionMaxTelemetryChanged(_missionMaxTelemetry);
if (!qFuzzyCompare(_missionFlightStatus.maxTelemetryDistance, missionMaxTelemetry)) {
_missionFlightStatus.maxTelemetryDistance = missionMaxTelemetry;
emit missionMaxTelemetryChanged(missionMaxTelemetry);
}
}
void MissionController::_setMissionDistance(double missionDistance)
{
if (!qFuzzyCompare(_missionDistance, missionDistance)) {
_missionDistance = missionDistance;
emit missionDistanceChanged(_missionDistance);
if (!qFuzzyCompare(_missionFlightStatus.totalDistance, missionDistance)) {
_missionFlightStatus.totalDistance = missionDistance;
emit missionDistanceChanged(missionDistance);
}
}
void MissionController::_setMissionTime(double missionTime)
{
if (!qFuzzyCompare(_missionTime, missionTime)) {
_missionTime = missionTime;
if (!qFuzzyCompare(_missionFlightStatus.totalTime, missionTime)) {
_missionFlightStatus.totalTime = missionTime;
emit missionTimeChanged();
}
}
void MissionController::_setMissionHoverTime(double missionHoverTime)
{
if (!qFuzzyCompare(_missionHoverTime, missionHoverTime)) {
_missionHoverTime = missionHoverTime;
if (!qFuzzyCompare(_missionFlightStatus.hoverTime, missionHoverTime)) {
_missionFlightStatus.hoverTime = missionHoverTime;
emit missionHoverTimeChanged();
}
}
void MissionController::_setMissionHoverDistance(double missionHoverDistance)
{
if (!qFuzzyCompare(_missionHoverDistance, missionHoverDistance)) {
_missionHoverDistance = missionHoverDistance;
emit missionHoverDistanceChanged(_missionHoverDistance);
if (!qFuzzyCompare(_missionFlightStatus.hoverDistance, missionHoverDistance)) {
_missionFlightStatus.hoverDistance = missionHoverDistance;
emit missionHoverDistanceChanged(missionHoverDistance);
}
}
void MissionController::_setMissionCruiseTime(double missionCruiseTime)
{
if (!qFuzzyCompare(_missionCruiseTime, missionCruiseTime)) {
_missionCruiseTime = missionCruiseTime;
if (!qFuzzyCompare(_missionFlightStatus.cruiseTime, missionCruiseTime)) {
_missionFlightStatus.cruiseTime = missionCruiseTime;
emit missionCruiseTimeChanged();
}
}
void MissionController::_setMissionCruiseDistance(double missionCruiseDistance)
{
if (!qFuzzyCompare(_missionCruiseDistance, missionCruiseDistance)) {
_missionCruiseDistance = missionCruiseDistance;
emit missionCruiseDistanceChanged(_missionCruiseDistance);
if (!qFuzzyCompare(_missionFlightStatus.cruiseDistance, missionCruiseDistance)) {
_missionFlightStatus.cruiseDistance = missionCruiseDistance;
emit missionCruiseDistanceChanged(missionCruiseDistance);
}
}
......@@ -1445,7 +1507,7 @@ QGeoCoordinate MissionController::plannedHomePosition(void)
void MissionController::_homeCoordinateChanged(void)
{
emit plannedHomePositionChanged(plannedHomePosition());
_recalcAltitudeRangeBearing();
_recalcMissionFlightStatus();
}
QString MissionController::fileExtension(void) const
......@@ -1453,24 +1515,6 @@ QString MissionController::fileExtension(void) const
return QGCApplication::missionFileExtension;
}
double MissionController::cruiseSpeed(void) const
{
if (_activeVehicle) {
return _activeVehicle->cruiseSpeed();
} else {
return 0.0f;
}
}
double MissionController::hoverSpeed(void) const
{
if (_activeVehicle) {
return _activeVehicle->hoverSpeed();
} else {
return 0.0f;
}
}
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
int scanIndex = 0;
......
......@@ -16,11 +16,11 @@
#include "Vehicle.h"
#include "QGCLoggingCategory.h"
#include "MavlinkQmlSingleton.h"
#include "VisualMissionItem.h"
#include <QHash>
class CoordinateVector;
class VisualMissionItem;
Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog)
......@@ -34,6 +34,20 @@ public:
MissionController(QObject* parent = NULL);
~MissionController();
typedef struct {
double maxTelemetryDistance;
double totalDistance;
double totalTime;
double hoverDistance;
double hoverTime;
double cruiseDistance;
double cruiseTime;
double cruiseSpeed;
double hoverSpeed;
double vehicleSpeed; //</ Either cruise or hover speed based on vehicle type and vtol state
double gimbalYaw; ///< NaN signals yaw was never changed
} MissionFlightStatus_t;
// Mission settings
Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
......@@ -94,15 +108,13 @@ public:
QmlObjectListModel* visualItems (void) { return _visualItems; }
QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
double missionDistance (void) const { return _missionDistance; }
double missionTime (void) const { return _missionTime; }
double missionHoverDistance (void) const { return _missionHoverDistance; }
double missionHoverTime (void) const { return _missionHoverTime; }
double missionCruiseDistance (void) const { return _missionCruiseDistance; }
double missionCruiseTime (void) const { return _missionCruiseTime; }
double missionMaxTelemetry (void) const { return _missionMaxTelemetry; }
double cruiseSpeed (void) const;
double hoverSpeed (void) const;
double missionDistance (void) const { return _missionFlightStatus.totalDistance; }
double missionTime (void) const { return _missionFlightStatus.totalTime; }
double missionHoverDistance (void) const { return _missionFlightStatus.hoverDistance; }
double missionHoverTime (void) const { return _missionFlightStatus.hoverTime; }
double missionCruiseDistance (void) const { return _missionFlightStatus.cruiseDistance; }
double missionCruiseTime (void) const { return _missionFlightStatus.cruiseTime; }
double missionMaxTelemetry (void) const { return _missionFlightStatus.maxTelemetryDistance; }
signals:
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition);
......@@ -116,10 +128,6 @@ signals:
void missionCruiseDistanceChanged(double missionCruiseDistance);
void missionCruiseTimeChanged(void);
void missionMaxTelemetryChanged(double missionMaxTelemetry);
void cruiseDistanceChanged(double cruiseDistance);
void hoverDistanceChanged(double hoverDistance);
void cruiseSpeedChanged(double cruiseSpeed);
void hoverSpeedChanged(double hoverSpeed);
private slots:
void _newMissionItemsAvailableFromVehicle();
......@@ -129,7 +137,7 @@ private slots:
void _inProgressChanged(bool inProgress);
void _currentMissionItemChanged(int sequenceNumber);
void _recalcWaypointLines(void);
void _recalcAltitudeRangeBearing(void);
void _recalcMissionFlightStatus(void);
void _homeCoordinateChanged(void);
private:
......@@ -167,22 +175,16 @@ private:
void _activeVehicleSet(void) final;
private:
QmlObjectListModel* _visualItems;
QmlObjectListModel _waypointLines;
CoordVectHashTable _linesTable;
bool _firstItemsFromVehicle;
bool _missionItemsRequested;
bool _queuedSend;
double _missionDistance;
double _missionTime;
double _missionHoverDistance;
double _missionHoverTime;
double _missionCruiseDistance;
double _missionCruiseTime;
double _missionMaxTelemetry;
QString _surveyMissionItemName;
QString _fwLandingMissionItemName;
QStringList _complexMissionItemNames;
QmlObjectListModel* _visualItems;
QmlObjectListModel _waypointLines;
CoordVectHashTable _linesTable;
bool _firstItemsFromVehicle;
bool _missionItemsRequested;
bool _queuedSend;
MissionFlightStatus_t _missionFlightStatus;
QString _surveyMissionItemName;
QString _fwLandingMissionItemName;
QStringList _complexMissionItemNames;
static const char* _settingsGroup;
......
......@@ -53,6 +53,7 @@ MissionItem::MissionItem(QObject* parent)
setAutoContinue(true);
connect(&_param2Fact, &Fact::rawValueChanged, this, &MissionItem::_param2Changed);
connect(&_param3Fact, &Fact::rawValueChanged, this, &MissionItem::_param3Changed);
}
MissionItem::MissionItem(int sequenceNumber,
......@@ -99,6 +100,7 @@ MissionItem::MissionItem(int sequenceNumber,
_param7Fact.setRawValue(param7);
connect(&_param2Fact, &Fact::rawValueChanged, this, &MissionItem::_param2Changed);
connect(&_param3Fact, &Fact::rawValueChanged, this, &MissionItem::_param3Changed);
}
MissionItem::MissionItem(const MissionItem& other, QObject* parent)
......@@ -123,6 +125,7 @@ MissionItem::MissionItem(const MissionItem& other, QObject* parent)
*this = other;
connect(&_param2Fact, &Fact::rawValueChanged, this, &MissionItem::_param2Changed);
connect(&_param3Fact, &Fact::rawValueChanged, this, &MissionItem::_param3Changed);
}
const MissionItem& MissionItem::operator=(const MissionItem& other)
......@@ -384,7 +387,7 @@ QGeoCoordinate MissionItem::coordinate(void) const
return QGeoCoordinate(param5(), param6(), param7());
}
double MissionItem::flightSpeed(void) const
double MissionItem::specifiedFlightSpeed(void) const
{
double flightSpeed = std::numeric_limits<double>::quiet_NaN();
......@@ -395,9 +398,33 @@ double MissionItem::flightSpeed(void) const
return flightSpeed;
}
double MissionItem::specifiedGimbalYaw(void) const
{
double gimbalYaw = std::numeric_limits<double>::quiet_NaN();
if (_commandFact.rawValue().toInt() == MAV_CMD_DO_MOUNT_CONTROL && _param7Fact.rawValue().toInt() == MAV_MOUNT_MODE_MAVLINK_TARGETING) {
gimbalYaw = _param3Fact.rawValue().toDouble();
}
return gimbalYaw;
}
void MissionItem::_param2Changed(QVariant value)
{
if (_commandFact.rawValue().toInt() == MAV_CMD_DO_CHANGE_SPEED && _param2Fact.rawValue().toDouble() > 0) {
emit flightSpeedChanged(value.toDouble());
Q_UNUSED(value);
double flightSpeed = specifiedFlightSpeed();
if (!qIsNaN(flightSpeed)) {
emit specifiedFlightSpeedChanged(flightSpeed);
}
}
void MissionItem::_param3Changed(QVariant value)
{
Q_UNUSED(value);
double gimbalYaw = specifiedGimbalYaw();
if (!qIsNaN(gimbalYaw)) {
emit specifiedGimbalYawChanged(gimbalYaw);
}
}
......@@ -77,7 +77,10 @@ public:
int doJumpId (void) const { return _doJumpId; }
/// @return Flight speed change value if this item supports it. If not it returns NaN.
double flightSpeed (void) const;
double specifiedFlightSpeed(void) const;
/// @return Flight gimbal yaw change value if this item supports it. If not it returns NaN.
double specifiedGimbalYaw(void) const;
void setCommand (MAV_CMD command);
void setSequenceNumber (int sequenceNumber);
......@@ -100,13 +103,15 @@ public:
bool relativeAltitude(void) const { return frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT; }
signals:
void isCurrentItemChanged (bool isCurrentItem);
void sequenceNumberChanged (int sequenceNumber);
void flightSpeedChanged (double flightSpeed);
void isCurrentItemChanged (bool isCurrentItem);
void sequenceNumberChanged (int sequenceNumber);
void specifiedFlightSpeedChanged(double flightSpeed);
void specifiedGimbalYawChanged (double gimbalYaw);
private slots:
void _param2Changed (QVariant value);
void _param3Changed (QVariant value);
private:
bool _convertJsonV1ToV2(const QJsonObject& json, QJsonObject& v2Json, QString& errorString);
......
......@@ -76,6 +76,10 @@ MissionSettingsComplexItem::MissionSettingsComplexItem(Vehicle* vehicle, QObject
connect(&_missionEndActionFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty);
connect(&_cameraSection, &CameraSection::dirtyChanged, this, &MissionSettingsComplexItem::_cameraSectionDirtyChanged);
connect(&_missionFlightSpeedFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::specifiedFlightSpeedChanged);
connect(&_cameraSection, &CameraSection::specifyGimbalChanged, this, &MissionSettingsComplexItem::specifiedGimbalYawChanged);
connect(&_cameraSection, &CameraSection::specifiedGimbalYawChanged, this, &MissionSettingsComplexItem::specifiedGimbalYawChanged);
}
......@@ -266,12 +270,6 @@ double MissionSettingsComplexItem::complexDistance(void) const
return 0;
}
void MissionSettingsComplexItem::setCruiseSpeed(double cruiseSpeed)
{
// We don't care about cruise speed
Q_UNUSED(cruiseSpeed);
}
void MissionSettingsComplexItem::_setDirty(void)
{
setDirty(true);
......@@ -310,3 +308,13 @@ void MissionSettingsComplexItem::_cameraSectionDirtyChanged(bool dirty)
setDirty(true);
}
}
double MissionSettingsComplexItem::specifiedFlightSpeed(void)
{
return _specifyMissionFlightSpeed ? _missionFlightSpeedFact.rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
}
double MissionSettingsComplexItem::specifiedGimbalYaw(void)
{
return _cameraSection.specifyGimbal() ? _cameraSection.gimbalYaw()->rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
}
......@@ -60,7 +60,6 @@ public:
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
double greatestDistanceTo (const QGeoCoordinate &other) const final;
void setCruiseSpeed (double cruiseSpeed) final;
QString mapVisualQML (void) const final { return QStringLiteral("MissionSettingsMapVisual.qml"); }
// Overrides from VisualMissionItem
......@@ -76,7 +75,8 @@ public:
QGeoCoordinate coordinate (void) const final;
QGeoCoordinate exitCoordinate (void) const final { return coordinate(); }
int sequenceNumber (void) const final { return _sequenceNumber; }
double flightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedFlightSpeed (void) final;
double specifiedGimbalYaw (void) final;
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
bool coordinateHasRelativeAltitude (void) const final { return true; }
......@@ -94,10 +94,10 @@ signals:
bool specifyMissionFlightSpeedChanged(bool specifyMissionFlightSpeed);
private slots:
void _setDirtyAndUpdateLastSequenceNumber(void);
void _setDirtyAndUpdateCoordinate(void);
void _setDirty(void);
void _cameraSectionDirtyChanged(bool dirty);
void _setDirtyAndUpdateLastSequenceNumber (void);
void _setDirtyAndUpdateCoordinate (void);
void _setDirty (void);
void _cameraSectionDirtyChanged (bool dirty);
private:
bool _specifyMissionFlightSpeed;
......
......@@ -75,7 +75,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
setDefaultsForCommand();
connect(&_missionItem, &MissionItem::flightSpeedChanged, this, &SimpleMissionItem::flightSpeedChanged);
connect(&_missionItem, &MissionItem::specifiedFlightSpeedChanged, this, &SimpleMissionItem::specifiedFlightSpeedChanged);
connect(this, &SimpleMissionItem::sequenceNumberChanged, this, &SimpleMissionItem::lastSequenceNumberChanged);
connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_setDirtyFromSignal);
......@@ -637,9 +637,14 @@ void SimpleMissionItem::setSequenceNumber(int sequenceNumber)
}
}
double SimpleMissionItem::flightSpeed(void)
double SimpleMissionItem::specifiedFlightSpeed(void)
{
return missionItem().flightSpeed();
return missionItem().specifiedFlightSpeed();
}
double SimpleMissionItem::specifiedGimbalYaw(void)
{
return _cameraSection->available() ? _cameraSection->specifiedGimbalYaw() : missionItem().specifiedGimbalYaw();
}
void SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle)
......@@ -671,7 +676,10 @@ void SimpleMissionItem::_updateCameraSection(void)
connect(_cameraSection, &CameraSection::dirtyChanged, this, &SimpleMissionItem::_cameraSectionDirtyChanged);
connect(_cameraSection, &CameraSection::availableChanged, this, &SimpleMissionItem::_updateLastSequenceNumber);
connect(_cameraSection, &CameraSection::missionItemCountChanged, this, &SimpleMissionItem::_updateLastSequenceNumber);
connect(_cameraSection, &CameraSection::missionItemCountChanged, this, &SimpleMissionItem::_updateLastSequenceNumber);
connect(_cameraSection, &CameraSection::availableChanged, this, &SimpleMissionItem::specifiedGimbalYawChanged);
connect(_cameraSection, &CameraSection::specifyGimbalChanged, this, &SimpleMissionItem::specifiedGimbalYawChanged);
connect(_cameraSection, &CameraSection::specifiedGimbalYawChanged, this, &SimpleMissionItem::specifiedGimbalYawChanged);
emit cameraSectionChanged(_cameraSection);
}
......
......@@ -94,7 +94,8 @@ public:
QGeoCoordinate coordinate (void) const final { return _missionItem.coordinate(); }
QGeoCoordinate exitCoordinate (void) const final { return coordinate(); }
int sequenceNumber (void) const final { return _missionItem.sequenceNumber(); }
double flightSpeed (void) final;
double specifiedFlightSpeed (void) final;
double specifiedGimbalYaw (void) final;
QString mapVisualQML (void) const final { return QStringLiteral("SimpleItemMapVisual.qml"); }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
......
......@@ -122,12 +122,6 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
connect(&_cameraTriggerFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraTriggerChanged);
connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
// NULL check since object creation during unit testing passes NULL for vehicle
if (_vehicle) {
connect(_vehicle, &Vehicle::cruiseSpeedChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
connect(_vehicle, &Vehicle::hoverSpeedChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
}
}
void SurveyMissionItem::_setSurveyDistance(double surveyDistance)
......@@ -894,10 +888,11 @@ double SurveyMissionItem::timeBetweenShots(void) const
return _cruiseSpeed == 0 ? 0 : _cameraTriggerDistanceFact.rawValue().toDouble() / _cruiseSpeed;
}
void SurveyMissionItem::setCruiseSpeed(double cruiseSpeed)
void SurveyMissionItem::setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus)
{
if (!qFuzzyCompare(_cruiseSpeed, cruiseSpeed)) {
_cruiseSpeed = cruiseSpeed;
ComplexMissionItem::setMissionFlightStatus(missionFlightStatus);
if (!qFuzzyCompare(_cruiseSpeed, missionFlightStatus.vehicleSpeed)) {
_cruiseSpeed = missionFlightStatus.vehicleSpeed;
emit timeBetweenShotsChanged();
}
}
......@@ -100,7 +100,6 @@ public:
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
double greatestDistanceTo (const QGeoCoordinate &other) const final;
void setCruiseSpeed (double cruiseSpeed) final;
QString mapVisualQML (void) const final { return QStringLiteral("SurveyMapVisual.qml"); }
......@@ -117,8 +116,10 @@ public:
QGeoCoordinate coordinate (void) const final { return _coordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _exitCoordinate; }
int sequenceNumber (void) const final { return _sequenceNumber; }
double flightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedFlightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
bool coordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelativeFact.rawValue().toBool(); }
bool exitCoordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelativeFact.rawValue().toBool(); }
......
......@@ -31,6 +31,8 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent)
, _altPercent(0.0)
, _azimuth(0.0)
, _distance(0.0)
, _missionGimbalYaw(std::numeric_limits<double>::quiet_NaN())
, _missionVehicleYaw(std::numeric_limits<double>::quiet_NaN())
{
}
......@@ -117,3 +119,20 @@ void VisualMissionItem::setShowHomePosition(bool showHomePosition)
emit showHomePositionChanged(_showHomePosition);
}
}
void VisualMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
{
_missionFlightStatus = missionFlightStatus;
if (_missionFlightStatus.gimbalYaw != _missionGimbalYaw) {
_missionGimbalYaw = _missionFlightStatus.gimbalYaw;
emit missionGimbalYawChanged(_missionGimbalYaw);
}
}
void VisualMissionItem::setMissionVehicleYaw(double vehicleYaw)
{
if (!qFuzzyCompare(_missionVehicleYaw, vehicleYaw)) {
_missionVehicleYaw = vehicleYaw;
emit missionVehicleYawChanged(_missionVehicleYaw);
}
}
......@@ -26,6 +26,7 @@
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
#include "Vehicle.h"
#include "MissionController.h"
class MissionItem;
......@@ -42,8 +43,31 @@ public:
const VisualMissionItem& operator=(const VisualMissionItem& other);
Q_PROPERTY(bool homePosition READ homePosition CONSTANT) ///< true: This item is being used as a home position indicator
Q_PROPERTY(bool showHomePosition READ showHomePosition WRITE setShowHomePosition NOTIFY showHomePositionChanged)
Q_PROPERTY(bool homePosition READ homePosition CONSTANT) ///< true: This item is being used as a home position indicator
Q_PROPERTY(bool showHomePosition READ showHomePosition WRITE setShowHomePosition NOTIFY showHomePositionChanged)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged) ///< This is the entry point for a waypoint line into the item. For a simple item it is also the location of the item
Q_PROPERTY(bool coordinateHasRelativeAltitude READ coordinateHasRelativeAltitude NOTIFY coordinateHasRelativeAltitudeChanged) ///< true: coordinate.latitude is relative to home altitude
Q_PROPERTY(QGeoCoordinate exitCoordinate READ exitCoordinate NOTIFY exitCoordinateChanged) ///< This is the exit point for a waypoint line coming out of the item.
Q_PROPERTY(bool exitCoordinateHasRelativeAltitude READ exitCoordinateHasRelativeAltitude NOTIFY exitCoordinateHasRelativeAltitudeChanged) ///< true: coordinate.latitude is relative to home altitude
Q_PROPERTY(bool exitCoordinateSameAsEntry READ exitCoordinateSameAsEntry NOTIFY exitCoordinateSameAsEntryChanged) ///< true: exitCoordinate and coordinate are the same value
Q_PROPERTY(QString commandDescription READ commandDescription NOTIFY commandDescriptionChanged)
Q_PROPERTY(QString commandName READ commandName NOTIFY commandNameChanged)
Q_PROPERTY(QString abbreviation READ abbreviation NOTIFY abbreviationChanged)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< Item is dirty and requires save/send
Q_PROPERTY(bool isCurrentItem READ isCurrentItem WRITE setIsCurrentItem NOTIFY isCurrentItemChanged)
Q_PROPERTY(int sequenceNumber READ sequenceNumber WRITE setSequenceNumber NOTIFY sequenceNumberChanged)
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate NOTIFY specifiesCoordinateChanged) ///< true: Item is associated with a coordinate position
Q_PROPERTY(bool isStandaloneCoordinate READ isStandaloneCoordinate NOTIFY isStandaloneCoordinateChanged) ///< true: Waypoint line does not go through item
Q_PROPERTY(bool specifiesAltitudeOnly READ specifiesAltitudeOnly NOTIFY specifiesAltitudeOnlyChanged) ///< true: Item has altitude only, no full coordinate
Q_PROPERTY(bool isSimpleItem READ isSimpleItem NOTIFY isSimpleItemChanged) ///< Simple or Complex MissionItem
Q_PROPERTY(QString editorQml MEMBER _editorQml CONSTANT) ///< Qml code for editing this item
Q_PROPERTY(QString mapVisualQML READ mapVisualQML CONSTANT) ///< QMl code for map visuals
Q_PROPERTY(QmlObjectListModel* childItems READ childItems CONSTANT)
Q_PROPERTY(double specifiedFlightSpeed READ specifiedFlightSpeed NOTIFY specifiedFlightSpeedChanged) ///< NaN if this item does not specify flight speed
Q_PROPERTY(double specifiedGimbalYaw READ specifiedGimbalYaw NOTIFY specifiedGimbalYawChanged) ///< NaN if this item goes not specify gimbal yaw
Q_PROPERTY(double missionGimbalYaw READ missionGimbalYaw NOTIFY missionGimbalYawChanged) ///< Current gimbal yaw state at this point in mission
Q_PROPERTY(double missionVehicleYaw READ missionVehicleYaw NOTIFY missionVehicleYawChanged) ///< Expected vehicle yaw at this point in mission
Q_PROPERTY(double showMissionGimbalYaw READ showMissionGimbalYaw NOTIFY missionGimbalYawChanged) ///< true: Show gimbal yaw position on map indicators
// The following properties are calculated/set by the MissionController recalc methods
......@@ -52,45 +76,6 @@ public:
Q_PROPERTY(double azimuth READ azimuth WRITE setAzimuth NOTIFY azimuthChanged) ///< Azimuth to previous waypoint
Q_PROPERTY(double distance READ distance WRITE setDistance NOTIFY distanceChanged) ///< Distance to previous waypoint
/// This property returns whether the item supports changing flight speed. If it does not it will return NaN.
Q_PROPERTY(double flightSpeed READ flightSpeed NOTIFY flightSpeedChanged)
// Visual mission items have two coordinates associated with them:
/// This is the entry point for a waypoint line into the item. For a simple item it is also the location of the item
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged)
/// @return true: coordinate.latitude is relative to home altitude
Q_PROPERTY(bool coordinateHasRelativeAltitude READ coordinateHasRelativeAltitude NOTIFY coordinateHasRelativeAltitudeChanged)
/// This is the exit point for a waypoint line coming out of the item.
Q_PROPERTY(QGeoCoordinate exitCoordinate READ exitCoordinate NOTIFY exitCoordinateChanged)
/// @return true: coordinate.latitude is relative to home altitude
Q_PROPERTY(bool exitCoordinateHasRelativeAltitude READ exitCoordinateHasRelativeAltitude NOTIFY exitCoordinateHasRelativeAltitudeChanged)
/// @return true: exitCoordinate and coordinate are the same value
Q_PROPERTY(bool exitCoordinateSameAsEntry READ exitCoordinateSameAsEntry NOTIFY exitCoordinateSameAsEntryChanged)
// General properties associated with all types of visual mission items
Q_PROPERTY(QString commandDescription READ commandDescription NOTIFY commandDescriptionChanged)
Q_PROPERTY(QString commandName READ commandName NOTIFY commandNameChanged)
Q_PROPERTY(QString abbreviation READ abbreviation NOTIFY abbreviationChanged)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< Item is dirty and requires save/send
Q_PROPERTY(bool isCurrentItem READ isCurrentItem WRITE setIsCurrentItem NOTIFY isCurrentItemChanged)
Q_PROPERTY(int sequenceNumber READ sequenceNumber WRITE setSequenceNumber NOTIFY sequenceNumberChanged)
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate NOTIFY specifiesCoordinateChanged) ///< true: Item is associated with a coordinate position
Q_PROPERTY(bool isStandaloneCoordinate READ isStandaloneCoordinate NOTIFY isStandaloneCoordinateChanged) ///< true: Waypoint line does not go through item
Q_PROPERTY(bool specifiesAltitudeOnly READ specifiesAltitudeOnly NOTIFY specifiesAltitudeOnlyChanged) ///< true: Item has altitude only, no full coordinate
Q_PROPERTY(bool isSimpleItem READ isSimpleItem NOTIFY isSimpleItemChanged) ///< Simple or Complex MissionItem
Q_PROPERTY(QString editorQml MEMBER _editorQml CONSTANT) ///< Qml code for editing this item
Q_PROPERTY(QString mapVisualQML READ mapVisualQML CONSTANT) ///< QMl code for map visuals
/// List of child mission items. Child mission item are subsequent mision items which do not specify a coordinate. They
/// are shown next to the exitCoordinate indidcator in the ui.
Q_PROPERTY(QmlObjectListModel* childItems READ childItems CONSTANT)
// Property accesors
bool homePosition (void) const { return _homePositionSpecialCase; }
......@@ -127,7 +112,12 @@ public:
virtual QGeoCoordinate coordinate (void) const = 0;
virtual QGeoCoordinate exitCoordinate (void) const = 0;
virtual int sequenceNumber (void) const = 0;
virtual double flightSpeed (void) = 0;
virtual double specifiedFlightSpeed (void) = 0;
virtual double specifiedGimbalYaw (void) = 0;
/// Update item to mission flight status at point where this item appears in mission.
/// IMPORTANT: Overrides must call base class implementation
virtual void setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus);
virtual bool coordinateHasRelativeAltitude (void) const = 0;
virtual bool exitCoordinateHasRelativeAltitude (void) const = 0;
......@@ -150,6 +140,11 @@ public:
/// @param missionItemParent Parent object for newly created MissionItems
virtual void appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent) = 0;
double missionGimbalYaw (void) const { return _missionGimbalYaw; }
double missionVehicleYaw (void) const { return _missionVehicleYaw; }
bool showMissionGimbalYaw(void) const { return !qIsNaN(_missionGimbalYaw); }
void setMissionVehicleYaw(double vehicleYaw);
static const char* jsonTypeKey; ///< Json file attribute which specifies the item type
static const char* jsonTypeSimpleItemValue; ///< Item type is MISSION_ITEM
static const char* jsonTypeComplexItemValue; ///< Item type is Complex Item
......@@ -171,9 +166,12 @@ signals:
void isSimpleItemChanged (bool isSimpleItem);
void specifiesCoordinateChanged (void);
void isStandaloneCoordinateChanged (void);
void specifiesAltitudeOnlyChanged (void);
void flightSpeedChanged (double flightSpeed);
void specifiesAltitudeOnlyChanged (void);
void specifiedFlightSpeedChanged (void);
void specifiedGimbalYawChanged (void);
void lastSequenceNumberChanged (int sequenceNumber);
void missionGimbalYawChanged (double missionGimbalYaw);
void missionVehicleYawChanged (double missionVehicleYaw);
void coordinateHasRelativeAltitudeChanged (bool coordinateHasRelativeAltitude);
void exitCoordinateHasRelativeAltitudeChanged (bool exitCoordinateHasRelativeAltitude);
......@@ -190,6 +188,10 @@ protected:
double _azimuth; ///< Azimuth to previous waypoint
double _distance; ///< Distance to previous waypoint
QString _editorQml; ///< Qml resource for editing item
double _missionGimbalYaw;
double _missionVehicleYaw;
MissionController::MissionFlightStatus_t _missionFlightStatus;
/// This is used to reference any subsequent mission items which do not specify a coordinate.
QmlObjectListModel _childItems;
......
......@@ -7,34 +7,71 @@ import QGroundControl.Palette 1.0
Canvas {
id: root
width: _width + (_singleChar ? 0 : _label.width)
height: specifiesCoordinate ? (_width * 1.5) : _width
width: _width
height: width
signal clicked
property alias label: _label.text
property string label
property bool checked: false
property bool small: false
property var color: checked ? "green" : qgcPal.mapButtonHighlight
property real anchorPointX: _width / 2
property real anchorPointY: _width * 1.5
property real anchorPointY: _width / 2
property bool specifiesCoordinate: true
property real gimbalYaw
property real vehicleYaw
property bool showGimbalYaw: false
property real _width: small ? ScreenTools.defaultFontPixelHeight * ScreenTools.smallFontPointRatio * 1.25 : ScreenTools.defaultFontPixelHeight * 1.25
property bool _singleChar: _label.text.length <= 1
property real _width: showGimbalYaw ? _gimbalYawRadius * 2 : _indicatorRadius * 2
property bool _singleChar: _label.text.length <= 1
property real _gimbalYawRadius: ScreenTools.defaultFontPixelHeight
property real _indicatorRadius: small ? (ScreenTools.defaultFontPixelHeight * ScreenTools.smallFontPointRatio * 1.25 / 2) : (ScreenTools.defaultFontPixelHeight * 0.66)
property real _gimbalRadians: degreesToRadians(vehicleYaw + gimbalYaw - 90)
onColorChanged: requestPaint()
onColorChanged: requestPaint()
onShowGimbalYawChanged: requestPaint()
onGimbalYawChanged: requestPaint()
onVehicleYawChanged: requestPaint()
QGCPalette { id: qgcPal }
function degreesToRadians(degrees) {
return (Math.PI/180)*degrees
}
function paintGimbalYaw(context) {
if (showGimbalYaw) {
context.save()
context.globalAlpha = 0.75
context.beginPath()
context.moveTo(anchorPointX, anchorPointY)
context.arc(anchorPointX, anchorPointY, _gimbalYawRadius, _gimbalRadians + degreesToRadians(45), _gimbalRadians + degreesToRadians(-45), true /* clockwise */)
context.closePath()
context.fillStyle = "white"
context.fill()
context.restore()
}
}
function paintSingleCoordinate(context) {
context.beginPath()
context.arc(_width / 2, _width / 2, _width / 2, (Math.PI / 8) * 7, Math.PI / 8);
context.lineTo(_width / 2, _width * 1.5)
context.closePath()
context.fillStyle = color
context.fill()
}
function paintSingleNoCoordinate(context) {
context.arc(_width / 2, _width / 2, _width / 2, Math.PI * 2, 0);
context.save()
context.beginPath()
context.translate(anchorPointX, anchorPointY)
context.arc(0, 0, _indicatorRadius, Math.PI * 2, 0);
context.closePath()
context.fillStyle = color
context.fill()
context.restore()
}
function paintMultipleCoordinate(context) {
......@@ -47,8 +84,9 @@ Canvas {
onPaint: {
var context = getContext("2d")
context.reset()
context.beginPath()
context.clearRect(0, 0, width, height)
paintGimbalYaw(context)
/*
if (_singleChar) {
if (specifiesCoordinate) {
paintSingleCoordinate(context)
......@@ -58,19 +96,21 @@ Canvas {
} else {
paintMultipleCoordinate(context)
}
context.closePath()
context.fillStyle = color
context.fill()
*/
paintSingleNoCoordinate(context)
}
QGCLabel {
id: _label
x: Math.round((_width / 2) - (_singleChar ? (width / 2) : (ScreenTools.defaultFontPixelWidth / 2)))
y: Math.round((_width / 2) - (height / 2))
color: "white"
font.pointSize: small ? ScreenTools.smallFontPointSize : ScreenTools.defaultFontPointSize
onWidthChanged: requestPaint()
id: _label
anchors.centerIn: parent
width: _indicatorRadius * 2
height: width
horizontalAlignment: Text.AlignHCenter
verticalAlignment: Text.AlignVCenter
color: "white"
font.pointSize: ScreenTools.defaultFontPointSize
fontSizeMode: Text.HorizontalFit
text: label
}
QGCMouseArea {
......
......@@ -102,8 +102,8 @@ Vehicle::Vehicle(LinkInterface* link,
, _onboardControlSensorsUnhealthy(0)
, _gpsRawIntMessageAvailable(false)
, _globalPositionIntMessageAvailable(false)
, _cruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
, _hoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
, _defaultCruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
, _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
, _telemetryRRSSI(0)
, _telemetryLRSSI(0)
, _telemetryRXErrors(0)
......@@ -264,8 +264,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _onboardControlSensorsUnhealthy(0)
, _gpsRawIntMessageAvailable(false)
, _globalPositionIntMessageAvailable(false)
, _cruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
, _hoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
, _defaultCruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
, _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
, _vehicleCapabilitiesKnown(true)
, _supportsMissionItemInt(false)
, _connectionLost(false)
......@@ -382,14 +382,14 @@ void Vehicle::_offlineVehicleTypeSettingChanged(QVariant value)
void Vehicle::_offlineCruiseSpeedSettingChanged(QVariant value)
{
_cruiseSpeed = value.toDouble();
emit cruiseSpeedChanged(_cruiseSpeed);
_defaultCruiseSpeed = value.toDouble();
emit defaultCruiseSpeedChanged(_defaultCruiseSpeed);
}
void Vehicle::_offlineHoverSpeedSettingChanged(QVariant value)
{
_hoverSpeed = value.toDouble();
emit hoverSpeedChanged(_hoverSpeed);
_defaultHoverSpeed = value.toDouble();
emit defaultHoverSpeedChanged(_defaultHoverSpeed);
}
QString Vehicle::firmwareTypeString(void) const
......
......@@ -574,8 +574,8 @@ public:
QString missionFlightMode () const;
QString rtlFlightMode () const;
QString takeControlFlightMode () const;
double cruiseSpeed () const { return _cruiseSpeed; }
double hoverSpeed () const { return _hoverSpeed; }
double defaultCruiseSpeed () const { return _defaultCruiseSpeed; }
double defaultHoverSpeed () const { return _defaultHoverSpeed; }
QString firmwareTypeString () const;
QString vehicleTypeString () const;
int telemetryRRSSI () { return _telemetryRRSSI; }
......@@ -690,8 +690,8 @@ signals:
void prearmErrorChanged(const QString& prearmError);
void soloFirmwareChanged(bool soloFirmware);
void unhealthySensorsChanged(void);
void cruiseSpeedChanged(double cruiseSpeed);
void hoverSpeedChanged(double hoverSpeed);
void defaultCruiseSpeedChanged(double cruiseSpeed);
void defaultHoverSpeedChanged(double hoverSpeed);
void firmwareTypeChanged(void);
void vehicleTypeChanged(void);
......@@ -872,8 +872,8 @@ private:
uint32_t _onboardControlSensorsUnhealthy;
bool _gpsRawIntMessageAvailable;
bool _globalPositionIntMessageAvailable;
double _cruiseSpeed;
double _hoverSpeed;
double _defaultCruiseSpeed;
double _defaultHoverSpeed;
int _telemetryRRSSI;
int _telemetryLRSSI;
uint32_t _telemetryRXErrors;
......
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