Commit 4742849a authored by DonLakeFlyer's avatar DonLakeFlyer

Fix additionalTimeDelay calcs

parent 4dc7b9d6
......@@ -27,9 +27,6 @@ public:
/// Signals complexDistanceChanged
virtual double complexDistance(void) const = 0;
/// @return Amount of additional time delay in seconds needed to fly the complex item
virtual double additionalTimeDelay(void) const { return 0; }
/// Load the complex mission item from Json
/// @param complexObject Complex mission item json object
/// @param sequenceNumber Sequence number for first MISSION_ITEM in survey
......@@ -46,10 +43,13 @@ public:
/// This mission item attribute specifies the type of the complex item.
static const char* jsonComplexItemTypeKey;
// Overrides from VisualMissionItem
double additionalTimeDelay(void) const final { return 0; }
signals:
void complexDistanceChanged (void);
void greatestDistanceToChanged (void);
void additionalTimeDelayChanged (void);
};
#endif
......@@ -1193,26 +1193,6 @@ void MissionController::_addCruiseTime(double cruiseTime, double cruiseDistance,
_updateBatteryInfo(waypointIndex);
}
/// Adds additional time to a mission as specified by the command
void MissionController::_addCommandTimeDelay(SimpleMissionItem* simpleItem, bool vtolInHover)
{
double seconds = 0;
if (!simpleItem) {
return;
}
// This routine is currently quite minimal and only handles the simple cases.
switch ((int)simpleItem->command()) {
case MAV_CMD_NAV_WAYPOINT:
case MAV_CMD_CONDITION_DELAY:
seconds = simpleItem->missionItem().param1();
break;
}
_addTimeDistance(vtolInHover, 0, 0, seconds, 0, -1);
}
/// Adds the specified time to the appropriate hover or cruise time values.
/// @param vtolInHover true: vtol is currrent in hover mode
/// @param hoverTime Amount of time tp add to hover
......@@ -1367,8 +1347,7 @@ void MissionController::_recalcMissionFlightStatus()
}
}
// Check for command specific time delays
_addCommandTimeDelay(simpleItem, vtolInHover);
_addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
if (item->specifiesCoordinate()) {
// Keep track of the min/max altitude for all waypoints so we can show altitudes as a percentage
......@@ -1419,8 +1398,7 @@ void MissionController::_recalcMissionFlightStatus()
double hoverTime = distance / _missionFlightStatus.hoverSpeed;
double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
double extraTime = complexItem->additionalTimeDelay();
_addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
_addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
}
item->setMissionFlightStatus(_missionFlightStatus);
......@@ -1609,6 +1587,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(visualItem, &VisualMissionItem::terrainAltitudeChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence);
if (visualItem->isSimpleItem()) {
......@@ -1624,7 +1603,6 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
if (complexItem) {
connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged, this, &MissionController::_recalcMissionFlightStatus);
} else {
qWarning() << "ComplexMissionItem not found";
}
......
......@@ -254,7 +254,6 @@ private:
bool _loadItemsFromJson(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
void _initLoadedVisualItems(QmlObjectListModel* loadedVisualItems);
void _addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair);
void _addCommandTimeDelay(SimpleMissionItem* simpleItem, bool vtolInHover);
void _addTimeDistance(bool vtolInHover, double hoverTime, double cruiseTime, double extraTime, double distance, int seqNum);
int _insertComplexMissionItemWorker(ComplexMissionItem* complexItem, int i);
......
......@@ -205,6 +205,8 @@ void SimpleMissionItem::_connectSignals(void)
connect(&_missionItem._param6Fact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
connect(&_missionItem._param7Fact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
connect(&_missionItem._param1Fact, &Fact::valueChanged, this, &SimpleMissionItem::_possibleAdditionalTimeDelayChanged);
// The following changes may also change friendlyEditAllowed
connect(&_missionItem._autoContinueFact, &Fact::valueChanged, this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
......@@ -951,3 +953,28 @@ void SimpleMissionItem::setAltitudeMode(AltitudeMode altitudeMode)
emit altitudeModeChanged();
}
}
double SimpleMissionItem::additionalTimeDelay(void) const
{
switch (command()) {
case MAV_CMD_NAV_WAYPOINT:
case MAV_CMD_CONDITION_DELAY:
case MAV_CMD_NAV_DELAY:
return missionItem().param1();
default:
return 0;
}
}
void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void)
{
switch (command()) {
case MAV_CMD_NAV_WAYPOINT:
case MAV_CMD_CONDITION_DELAY:
case MAV_CMD_NAV_DELAY:
emit additionalTimeDelayChanged();
break;
}
return;
}
......@@ -122,6 +122,7 @@ public:
void applyNewAltitude (double newAltitude) final;
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
bool readyForSave (void) const final;
double additionalTimeDelay (void) const final;
bool coordinateHasRelativeAltitude (void) const final { return _missionItem.relativeAltitude(); }
bool exitCoordinateHasRelativeAltitude (void) const final { return coordinateHasRelativeAltitude(); }
......@@ -147,17 +148,18 @@ signals:
void supportsTerrainFrameChanged(void);
private slots:
void _setDirty (void);
void _sectionDirtyChanged (bool dirty);
void _sendCommandChanged (void);
void _sendCoordinateChanged (void);
void _sendFriendlyEditAllowedChanged(void);
void _altitudeChanged (void);
void _altitudeModeChanged (void);
void _terrainAltChanged (void);
void _updateLastSequenceNumber (void);
void _rebuildFacts (void);
void _rebuildTextFieldFacts (void);
void _setDirty (void);
void _sectionDirtyChanged (bool dirty);
void _sendCommandChanged (void);
void _sendCoordinateChanged (void);
void _sendFriendlyEditAllowedChanged (void);
void _altitudeChanged (void);
void _altitudeModeChanged (void);
void _terrainAltChanged (void);
void _updateLastSequenceNumber (void);
void _rebuildFacts (void);
void _rebuildTextFieldFacts (void);
void _possibleAdditionalTimeDelayChanged(void);
private:
void _connectSignals (void);
......
......@@ -442,108 +442,6 @@ void SurveyComplexItem::_adjustTransectsToEntryPointLocation(QList<QList<QGeoCoo
qCDebug(SurveyComplexItemLog) << "_adjustTransectsToEntryPointLocation Modified entry point:entryLocation" << transects.first().first() << _entryPoint;
}
#if 0
void SurveyComplexItem::_generateGrid(void)
{
if (_ignoreRecalc) {
return;
}
if (_mapPolygon.count() < 3 || _gridSpacingFact.rawValue().toDouble() <= 0) {
_clearInternal();
return;
}
_simpleGridPoints.clear();
_transectSegments.clear();
_reflyTransectSegments.clear();
_additionalFlightDelaySeconds = 0;
QList<QPointF> polygonPoints;
QList<QList<QPointF>> transectSegments;
// Convert polygon to NED
QGeoCoordinate tangentOrigin = _mapPolygon.pathModel().value<QGCQGeoCoordinate*>(0)->coordinate();
qCDebug(SurveyComplexItemLog) << "Convert polygon to NED - tangentOrigin" << tangentOrigin;
for (int i=0; i<_mapPolygon.count(); i++) {
double y, x, down;
QGeoCoordinate vertex = _mapPolygon.pathModel().value<QGCQGeoCoordinate*>(i)->coordinate();
if (i == 0) {
// This avoids a nan calculation that comes out of convertGeoToNed
x = y = 0;
} else {
convertGeoToNed(vertex, tangentOrigin, &y, &x, &down);
}
polygonPoints += QPointF(x, y);
qCDebug(SurveyComplexItemLog) << "vertex:x:y" << vertex << polygonPoints.last().x() << polygonPoints.last().y();
}
double coveredArea = 0.0;
for (int i=0; i<polygonPoints.count(); i++) {
if (i != 0) {
coveredArea += polygonPoints[i - 1].x() * polygonPoints[i].y() - polygonPoints[i].x() * polygonPoints[i -1].y();
} else {
coveredArea += polygonPoints.last().x() * polygonPoints[i].y() - polygonPoints[i].x() * polygonPoints.last().y();
}
}
_setCoveredArea(0.5 * fabs(coveredArea));
// Generate grid
int cameraShots = 0;
cameraShots += _gridGenerator(polygonPoints, transectSegments, false /* refly */);
_convertTransectToGeo(transectSegments, tangentOrigin, _transectSegments);
_adjustTransectsToEntryPointLocation(_transectSegments);
_appendGridPointsFromTransects(_transectSegments);
if (_refly90Degrees) {
transectSegments.clear();
cameraShots += _gridGenerator(polygonPoints, transectSegments, true /* refly */);
_convertTransectToGeo(transectSegments, tangentOrigin, _reflyTransectSegments);
_optimizeTransectsForShortestDistance(_transectSegments.last().last(), _reflyTransectSegments);
_appendGridPointsFromTransects(_reflyTransectSegments);
}
// Calc survey distance
double surveyDistance = 0.0;
for (int i=1; i<_simpleGridPoints.count(); i++) {
QGeoCoordinate coord1 = _simpleGridPoints[i-1].value<QGeoCoordinate>();
QGeoCoordinate coord2 = _simpleGridPoints[i].value<QGeoCoordinate>();
surveyDistance += coord1.distanceTo(coord2);
}
_setSurveyDistance(surveyDistance);
if (cameraShots == 0 && _triggerCamera()) {
cameraShots = (int)floor(surveyDistance / _triggerDistance());
// Take into account immediate camera trigger at waypoint entry
cameraShots++;
}
_setCameraShots(cameraShots);
if (_hoverAndCaptureEnabled()) {
_additionalFlightDelaySeconds = cameraShots * _hoverAndCaptureDelaySeconds;
}
emit additionalTimeDelayChanged();
emit gridPointsChanged();
// Determine command count for lastSequenceNumber
_missionCommandCount = _calcMissionCommandCount(_transectSegments);
_missionCommandCount += _calcMissionCommandCount(_reflyTransectSegments);
emit lastSequenceNumberChanged(lastSequenceNumber());
// Set exit coordinate
if (_simpleGridPoints.count()) {
QGeoCoordinate coordinate = _simpleGridPoints.first().value<QGeoCoordinate>();
coordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
setCoordinate(coordinate);
QGeoCoordinate exitCoordinate = _simpleGridPoints.last().value<QGeoCoordinate>();
exitCoordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
_setExitCoordinate(exitCoordinate);
}
setDirty(true);
}
#endif
QPointF SurveyComplexItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle)
{
QPointF rotated;
......
......@@ -151,6 +151,9 @@ public:
/// Adjust the altitude of the item if appropriate to the new altitude.
virtual void applyNewAltitude(double newAltitude) = 0;
/// @return Amount of additional time delay in seconds needed to fly this item
virtual double additionalTimeDelay(void) const = 0;
double missionGimbalYaw (void) const { return _missionGimbalYaw; }
double missionVehicleYaw (void) const { return _missionVehicleYaw; }
void setMissionVehicleYaw(double vehicleYaw);
......@@ -184,6 +187,7 @@ signals:
void missionGimbalYawChanged (double missionGimbalYaw);
void missionVehicleYawChanged (double missionVehicleYaw);
void terrainAltitudeChanged (double terrainAltitude);
void additionalTimeDelayChanged (void);
void coordinateHasRelativeAltitudeChanged (bool coordinateHasRelativeAltitude);
void exitCoordinateHasRelativeAltitudeChanged (bool exitCoordinateHasRelativeAltitude);
......
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