Commit c1feddf3 authored by Don Gagne's avatar Don Gagne

Flight time calculation for ascent/descent

parent 54c92f75
......@@ -866,10 +866,10 @@ void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionIte
// Convert to fixed altitudes
distanceOk = true;
if (currentItem->coordinateHasRelativeAltitude()) {
if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
currentCoord.setAltitude(homeAlt + currentCoord.altitude());
}
if (prevItem->exitCoordinateHasRelativeAltitude()) {
if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
prevCoord.setAltitude(homeAlt + prevCoord.altitude());
}
......@@ -993,7 +993,7 @@ void MissionController::_updateBatteryInfo(int waypointIndex)
_missionFlightStatus.hoverAmpsTotal = (_missionFlightStatus.hoverTime / 60.0) * _missionFlightStatus.hoverAmps;
_missionFlightStatus.cruiseAmpsTotal = (_missionFlightStatus.cruiseTime / 60.0) * _missionFlightStatus.cruiseAmps;
_missionFlightStatus.batteriesRequired = ceil((_missionFlightStatus.hoverAmpsTotal + _missionFlightStatus.cruiseAmpsTotal) / _missionFlightStatus.ampMinutesAvailable);
if (_missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
_missionFlightStatus.batteryChangePoint = waypointIndex - 1;
}
}
......@@ -1048,6 +1048,16 @@ void MissionController::_recalcMissionFlightStatus()
bool vtolInHover = true;
bool linkStartToHome = false;
bool linkEndToHome = false;
if (showHomePosition) {
SimpleMissionItem* lastItem = _visualItems->value<SimpleMissionItem*>(_visualItems->count() - 1);
if (lastItem && (int)lastItem->command() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
linkEndToHome = true;
} else {
linkEndToHome = _settingsItem->missionEndRTL();
}
}
for (int i=0; i<_visualItems->count(); i++) {
VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
......@@ -1093,6 +1103,13 @@ void MissionController::_recalcMissionFlightStatus()
if (firstCoordinateItem && simpleItem && simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
if (showHomePosition) {
linkStartToHome = true;
if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
// We have to special case takeoff, assuming vehicle takes off straight up to specified altitude
double azimuth, distance, altDifference;
_calcPrevWaypointValues(homePositionAltitude, _settingsItem, simpleItem, &azimuth, &distance, &altDifference);
double takeoffTime = qAbs(altDifference) / _appSettings->offlineEditingAscentSpeed()->rawValue().toDouble();
_addHoverTime(takeoffTime, 0, -1);
}
}
}
......@@ -1206,6 +1223,31 @@ void MissionController::_recalcMissionFlightStatus()
}
lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
if (linkEndToHome && lastCoordinateItem != _settingsItem) {
double azimuth, distance, altDifference;
_calcPrevWaypointValues(homePositionAltitude, lastCoordinateItem, _settingsItem, &azimuth, &distance, &altDifference);
// Calculate time/distance
double hoverTime = distance / _missionFlightStatus.hoverSpeed;
double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
double landTime = qAbs(altDifference) / _appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();
if (_controllerVehicle->vtol()) {
if (vtolInHover) {
_addHoverTime(hoverTime, distance, -1);
_addHoverTime(landTime, 0, -1);
} else {
_addCruiseTime(cruiseTime, distance, -1);
}
} else {
if (_controllerVehicle->multiRotor()) {
_addHoverTime(hoverTime, distance, -1);
_addHoverTime(landTime, 0, -1);
} else {
_addCruiseTime(cruiseTime, distance, -1);
}
}
}
if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
_missionFlightStatus.batteryChangePoint = 0;
}
......
......@@ -189,7 +189,7 @@ private:
void _initVisualItem(VisualMissionItem* item);
void _deinitVisualItem(VisualMissionItem* item);
void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle);
static void _calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference);
void _calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference);
static double _calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem);
bool _findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame);
static double _normalizeLat(double lat);
......
......@@ -83,17 +83,11 @@ Rectangle {
anchors.right: parent ? parent.right : undefined
anchors.top: parent ? parent.top : undefined
spacing: _margin
SectionHeader {
id: missionDefaultsSectionHeader
text: qsTr("Mission Defaults")
checked: true
}
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: missionDefaultsSectionHeader.checked
GridLayout {
anchors.left: parent.left
......@@ -128,7 +122,7 @@ Rectangle {
CameraSection {
id: cameraSection
checked: true
checked: false
}
QGCLabel {
......
......@@ -18,7 +18,7 @@
{
"name": "OfflineEditingCruiseSpeed",
"shortDescription": "Offline editing cruise speed",
"longDescription": "This value defines the cruising speed for forward flight vehicles for use in calculating mission duration when not connected to a vehicle.",
"longDescription": "This value defines the cruising speed for forward flight vehicles for use in calculating mission duration.",
"type": "double",
"defaultValue": 15.0,
"min": 1.0,
......@@ -28,13 +28,33 @@
{
"name": "OfflineEditingHoverSpeed",
"shortDescription": "Offline editing hover speed",
"longDescription": "This value defines the cruising speed for multi-rotor vehicles for use in calculating mission duration when not connected to a vehicle.",
"longDescription": "This value defines the cruising speed for multi-rotor vehicles for use in calculating mission duration.",
"type": "double",
"defaultValue": 5.0,
"min": 1.0,
"units": "m/s",
"decimalPlaces": 2
},
{
"name": "OfflineEditingAscentSpeed",
"shortDescription": "Offline editing ascent speed",
"longDescription": "This value defines the ascent speed for multi-rotor vehicles for use in calculating mission duration.",
"type": "double",
"defaultValue": 2.6,
"min": 0.1,
"units": "m/s",
"decimalPlaces": 2
},
{
"name": "OfflineEditingDescentSpeed",
"shortDescription": "Offline editing descent speed",
"longDescription": "This value defines the cruising speed for multi-rotor vehicles for use in calculating mission duration.",
"type": "double",
"defaultValue": 0.9,
"min": 0.1,
"units": "m/s",
"decimalPlaces": 2
},
{
"name": "batteryPercentRemainingAnnounce",
"shortDescription": "Announce battery remaining percent",
......
......@@ -20,6 +20,8 @@ const char* AppSettings::offlineEditingFirmwareTypeSettingsName = "Offline
const char* AppSettings::offlineEditingVehicleTypeSettingsName = "OfflineEditingVehicleType";
const char* AppSettings::offlineEditingCruiseSpeedSettingsName = "OfflineEditingCruiseSpeed";
const char* AppSettings::offlineEditingHoverSpeedSettingsName = "OfflineEditingHoverSpeed";
const char* AppSettings::offlineEditingAscentSpeedSettingsName = "OfflineEditingAscentSpeed";
const char* AppSettings::offlineEditingDescentSpeedSettingsName = "OfflineEditingDescentSpeed";
const char* AppSettings::batteryPercentRemainingAnnounceSettingsName = "batteryPercentRemainingAnnounce";
const char* AppSettings::defaultMissionItemAltitudeSettingsName = "DefaultMissionItemAltitude";
const char* AppSettings::telemetrySaveName = "PromptFLightDataSave";
......@@ -56,6 +58,8 @@ AppSettings::AppSettings(QObject* parent)
, _offlineEditingVehicleTypeFact(NULL)
, _offlineEditingCruiseSpeedFact(NULL)
, _offlineEditingHoverSpeedFact(NULL)
, _offlineEditingAscentSpeedFact(NULL)
, _offlineEditingDescentSpeedFact(NULL)
, _batteryPercentRemainingAnnounceFact(NULL)
, _defaultMissionItemAltitudeFact(NULL)
, _telemetrySaveFact(NULL)
......@@ -148,6 +152,22 @@ Fact* AppSettings::offlineEditingHoverSpeed(void)
return _offlineEditingHoverSpeedFact;
}
Fact* AppSettings::offlineEditingAscentSpeed(void)
{
if (!_offlineEditingAscentSpeedFact) {
_offlineEditingAscentSpeedFact = _createSettingsFact(offlineEditingAscentSpeedSettingsName);
}
return _offlineEditingAscentSpeedFact;
}
Fact* AppSettings::offlineEditingDescentSpeed(void)
{
if (!_offlineEditingDescentSpeedFact) {
_offlineEditingDescentSpeedFact = _createSettingsFact(offlineEditingDescentSpeedSettingsName);
}
return _offlineEditingDescentSpeedFact;
}
Fact* AppSettings::batteryPercentRemainingAnnounce(void)
{
if (!_batteryPercentRemainingAnnounceFact) {
......
......@@ -24,6 +24,8 @@ public:
Q_PROPERTY(Fact* offlineEditingVehicleType READ offlineEditingVehicleType CONSTANT)
Q_PROPERTY(Fact* offlineEditingCruiseSpeed READ offlineEditingCruiseSpeed CONSTANT)
Q_PROPERTY(Fact* offlineEditingHoverSpeed READ offlineEditingHoverSpeed CONSTANT)
Q_PROPERTY(Fact* offlineEditingAscentSpeed READ offlineEditingAscentSpeed CONSTANT)
Q_PROPERTY(Fact* offlineEditingDescentSpeed READ offlineEditingDescentSpeed CONSTANT)
Q_PROPERTY(Fact* batteryPercentRemainingAnnounce READ batteryPercentRemainingAnnounce CONSTANT)
Q_PROPERTY(Fact* defaultMissionItemAltitude READ defaultMissionItemAltitude CONSTANT)
Q_PROPERTY(Fact* telemetrySave READ telemetrySave CONSTANT)
......@@ -56,6 +58,8 @@ public:
Fact* offlineEditingVehicleType (void);
Fact* offlineEditingCruiseSpeed (void);
Fact* offlineEditingHoverSpeed (void);
Fact* offlineEditingAscentSpeed (void);
Fact* offlineEditingDescentSpeed (void);
Fact* batteryPercentRemainingAnnounce (void);
Fact* defaultMissionItemAltitude (void);
Fact* telemetrySave (void);
......@@ -86,6 +90,8 @@ public:
static const char* offlineEditingVehicleTypeSettingsName;
static const char* offlineEditingCruiseSpeedSettingsName;
static const char* offlineEditingHoverSpeedSettingsName;
static const char* offlineEditingAscentSpeedSettingsName;
static const char* offlineEditingDescentSpeedSettingsName;
static const char* batteryPercentRemainingAnnounceSettingsName;
static const char* defaultMissionItemAltitudeSettingsName;
static const char* telemetrySaveName;
......@@ -130,6 +136,8 @@ private:
SettingsFact* _offlineEditingVehicleTypeFact;
SettingsFact* _offlineEditingCruiseSpeedFact;
SettingsFact* _offlineEditingHoverSpeedFact;
SettingsFact* _offlineEditingAscentSpeedFact;
SettingsFact* _offlineEditingDescentSpeedFact;
SettingsFact* _batteryPercentRemainingAnnounceFact;
SettingsFact* _defaultMissionItemAltitudeFact;
SettingsFact* _telemetrySaveFact;
......
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