QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MissionFlightStatusCalculator.cc
Go to the documentation of this file.
2#include "Vehicle.h"
3#include "FirmwarePlugin.h"
5#include "VisualMissionItem.h"
6#include "SimpleMissionItem.h"
9#include "AppSettings.h"
10#include "PlanViewSettings.h"
11#include "SettingsManager.h"
12
13#include <QtMath>
14
15void MissionFlightStatusCalculator::reset(Vehicle* controllerVehicle, Vehicle* managerVehicle, bool missionContainsVTOLTakeoff)
16{
17 _status.totalDistance = 0.0;
18 _status.plannedDistance = 0.0;
19 _status.maxTelemetryDistance = 0.0;
20 _status.totalTime = 0.0;
21 _status.hoverTime = 0.0;
22 _status.cruiseTime = 0.0;
23 _status.hoverDistance = 0.0;
24 _status.cruiseDistance = 0.0;
25 _status.cruiseSpeed = controllerVehicle->defaultCruiseSpeed();
26 _status.hoverSpeed = controllerVehicle->defaultHoverSpeed();
27 _status.vehicleSpeed = controllerVehicle->multiRotor() || managerVehicle->vtol() ? _status.hoverSpeed : _status.cruiseSpeed;
28 _status.vehicleYaw = qQNaN();
29 _status.gimbalYaw = qQNaN();
30 _status.gimbalPitch = qQNaN();
31 _status.mAhBattery = 0;
32 _status.hoverAmps = 0;
33 _status.cruiseAmps = 0;
34 _status.ampMinutesAvailable = 0;
35 _status.hoverAmpsTotal = 0;
36 _status.cruiseAmpsTotal = 0;
37 _status.batteryChangePoint = -1;
38 _status.batteriesRequired = -1;
40
41 controllerVehicle->firmwarePlugin()->batteryConsumptionData(controllerVehicle, _status.mAhBattery, _status.hoverAmps, _status.cruiseAmps);
42 if (_status.mAhBattery != 0) {
43 double batteryPercentRemainingAnnounce = SettingsManager::instance()->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toDouble();
44 _status.ampMinutesAvailable = static_cast<double>(_status.mAhBattery) / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
45 }
46}
47
49 MissionSettingsItem* settingsItem,
50 Vehicle* controllerVehicle,
51 Vehicle* managerVehicle,
52 AppSettings* appSettings,
53 PlanViewSettings* planViewSettings,
54 bool missionContainsVTOLTakeoff)
55{
56 bool firstCoordinateItem = true;
57 VisualMissionItem* lastFlyThroughVI = qobject_cast<VisualMissionItem*>(visualItems->get(0));
58
59 bool homePositionValid = settingsItem->coordinate().isValid();
60
61 // If home position is valid we can calculate distances between all waypoints.
62 // If home position is not valid we can only calculate distances between waypoints which are
63 // both relative altitude.
64
65 // No values for first item
66 lastFlyThroughVI->setAltDifference(0);
67 lastFlyThroughVI->setAzimuth(0);
68 lastFlyThroughVI->setDistance(0);
69 lastFlyThroughVI->setDistanceFromStart(0);
70
71 _minAMSLAltitude = _maxAMSLAltitude = qQNaN();
72
73 reset(controllerVehicle, managerVehicle, missionContainsVTOLTakeoff);
74
75 bool linkStartToHome = false;
76 bool foundRTL = false;
77 bool pastLandCommand = false;
78 double totalHorizontalDistance = 0;
79
80 for (int i=0; i<visualItems->count(); i++) {
81 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(i));
82 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
83 ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
84
85 if (simpleItem && simpleItem->mavCommand() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
86 foundRTL = true;
87 }
88
89 // Assume the worst
90 item->setAzimuth(0);
91 item->setDistance(0);
92 item->setDistanceFromStart(0);
93
94 // Gimbal states reflect the state AFTER executing the item
95
96 // ROI commands cancel out previous gimbal yaw/pitch
97 if (simpleItem) {
98 switch (simpleItem->command()) {
99 case MAV_CMD_NAV_ROI:
100 case MAV_CMD_DO_SET_ROI_LOCATION:
101 case MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET:
102 case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW:
103 _status.gimbalYaw = qQNaN();
104 _status.gimbalPitch = qQNaN();
105 break;
106 default:
107 break;
108 }
109 }
110
111 // Look for specific gimbal changes
112 double gimbalYaw = item->specifiedGimbalYaw();
113 if (!qIsNaN(gimbalYaw) || planViewSettings->showGimbalOnlyWhenSet()->rawValue().toBool()) {
114 _status.gimbalYaw = gimbalYaw;
115 }
116 double gimbalPitch = item->specifiedGimbalPitch();
117 if (!qIsNaN(gimbalPitch) || planViewSettings->showGimbalOnlyWhenSet()->rawValue().toBool()) {
118 _status.gimbalPitch = gimbalPitch;
119 }
120
121 // We don't need to do any more processing if:
122 // Mission Settings Item
123 // We are after an RTL command
124 if (i != 0 && !foundRTL) {
125 // We must set the mission flight status prior to querying for any values from the item. This is because things like
126 // current speed, gimbal, vtol state impact the values.
127 item->setMissionFlightStatus(_status);
128
129 // Link back to home if first item is takeoff and we have home position
130 if (firstCoordinateItem && simpleItem && (simpleItem->mavCommand() == MAV_CMD_NAV_TAKEOFF || simpleItem->mavCommand() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
131 if (homePositionValid) {
132 linkStartToHome = true;
133 if (controllerVehicle->multiRotor() || controllerVehicle->vtol()) {
134 // We have to special case takeoff, assuming vehicle takes off straight up to specified altitude
135 double azimuth, distance, altDifference;
136 calcPrevWaypointValues(settingsItem, simpleItem, &azimuth, &distance, &altDifference);
137 double takeoffTime = qAbs(altDifference) / appSettings->offlineEditingAscentSpeed()->rawValue().toDouble();
138 _addHoverTime(takeoffTime, 0, -1);
139 }
140 }
141 }
142
143 if (!pastLandCommand)
144 _addTimeDistance(controllerVehicle, _status.vtolMode == QGCMAVLink::VehicleClassMultiRotor, 0, 0, item->additionalTimeDelay(), 0, -1);
145
146 if (item->specifiesCoordinate()) {
147
148 // Keep track of the min/max AMSL altitude for entire mission so we can calculate altitude percentages in terrain status display
149 if (simpleItem) {
150 double amslAltitude = item->amslEntryAlt();
151 _minAMSLAltitude = std::fmin(_minAMSLAltitude, amslAltitude);
152 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, amslAltitude);
153 } else {
154 // Complex item
155 double complexMinAMSLAltitude = complexItem->minAMSLAltitude();
156 double complexMaxAMSLAltitude = complexItem->maxAMSLAltitude();
157 _minAMSLAltitude = std::fmin(_minAMSLAltitude, complexMinAMSLAltitude);
158 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, complexMaxAMSLAltitude);
159 }
160
161 if (!item->isStandaloneCoordinate()) {
162 firstCoordinateItem = false;
163
164 // Update vehicle yaw assuming direction to next waypoint and/or mission item change
165 if (simpleItem) {
166 double newVehicleYaw = simpleItem->specifiedVehicleYaw();
167 if (qIsNaN(newVehicleYaw)) {
168 // No specific vehicle yaw set. Current vehicle yaw is determined from flight path segment direction.
169 if (simpleItem != lastFlyThroughVI) {
170 _status.vehicleYaw = lastFlyThroughVI->exitCoordinate().azimuthTo(simpleItem->entryCoordinate());
171 }
172 } else {
173 _status.vehicleYaw = newVehicleYaw;
174 }
175 simpleItem->setMissionVehicleYaw(_status.vehicleYaw);
176 }
177
178 if (lastFlyThroughVI != settingsItem || linkStartToHome) {
179 // This is a subsequent waypoint or we are forcing the first waypoint back to home
180 double azimuth, distance, altDifference;
181
182 calcPrevWaypointValues(item, lastFlyThroughVI, &azimuth, &distance, &altDifference);
183
184 // If the last waypoint was a land command, there's a discontinuity at this point
185 if (!lastFlyThroughVI->isLandCommand()) {
186 totalHorizontalDistance += distance;
187 item->setDistance(distance);
188
189 if (!pastLandCommand) {
190 // Calculate time/distance
191 double hoverTime = distance / _status.hoverSpeed;
192 double cruiseTime = distance / _status.cruiseSpeed;
193 _addTimeDistance(controllerVehicle, _status.vtolMode == QGCMAVLink::VehicleClassMultiRotor, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
194 }
195 }
196
197 item->setAltDifference(altDifference);
198 item->setAzimuth(azimuth);
199 item->setDistanceFromStart(totalHorizontalDistance);
200
201 _status.maxTelemetryDistance = qMax(_status.maxTelemetryDistance, calcDistanceToHome(item, settingsItem));
202 }
203
204 if (complexItem) {
205 // Add in distance/time inside complex items as well
206 double distance = complexItem->complexDistance();
207 _status.maxTelemetryDistance = qMax(_status.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
208
209 if (!pastLandCommand) {
210 double hoverTime = distance / _status.hoverSpeed;
211 double cruiseTime = distance / _status.cruiseSpeed;
212 _addTimeDistance(controllerVehicle, _status.vtolMode == QGCMAVLink::VehicleClassMultiRotor, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
213 }
214
215 totalHorizontalDistance += distance;
216 }
217
218
219 lastFlyThroughVI = item;
220 }
221 }
222 }
223
224 // Speed, VTOL states changes are processed last since they take affect on the next item
225
226 double newSpeed = item->specifiedFlightSpeed();
227 if (!qIsNaN(newSpeed)) {
228 if (controllerVehicle->multiRotor()) {
229 _status.hoverSpeed = newSpeed;
230 } else if (controllerVehicle->vtol()) {
232 _status.hoverSpeed = newSpeed;
233 } else {
234 _status.cruiseSpeed = newSpeed;
235 }
236 } else {
237 _status.cruiseSpeed = newSpeed;
238 }
239 _status.vehicleSpeed = newSpeed;
240 }
241
242 // Update VTOL state
243 if (simpleItem && controllerVehicle->vtol()) {
244 switch (simpleItem->command()) {
245 case MAV_CMD_NAV_TAKEOFF: // This will do a fixed wing style takeoff
246 case MAV_CMD_NAV_VTOL_TAKEOFF: // Vehicle goes straight up and then transitions to FW
247 case MAV_CMD_NAV_LAND:
249 break;
250 case MAV_CMD_NAV_VTOL_LAND:
252 break;
253 case MAV_CMD_DO_VTOL_TRANSITION:
254 {
255 int transitionState = simpleItem->missionItem().param1();
256 if (transitionState == MAV_VTOL_STATE_MC) {
258 } else if (transitionState == MAV_VTOL_STATE_FW) {
260 }
261 }
262 break;
263 default:
264 break;
265 }
266 }
267
268 if (item->isLandCommand()) {
269 pastLandCommand = true;
270 }
271 }
272 lastFlyThroughVI->setMissionVehicleYaw(_status.vehicleYaw);
273
274 // Add the information for the final segment back to home
275 if (foundRTL && lastFlyThroughVI != settingsItem && homePositionValid) {
276 double azimuth, distance, altDifference;
277 calcPrevWaypointValues(lastFlyThroughVI, settingsItem, &azimuth, &distance, &altDifference);
278
279 if (!pastLandCommand) {
280 // Calculate time/distance
281 double hoverTime = distance / _status.hoverSpeed;
282 double cruiseTime = distance / _status.cruiseSpeed;
283 double landTime = qAbs(altDifference) / appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();
284 _addTimeDistance(controllerVehicle, _status.vtolMode == QGCMAVLink::VehicleClassMultiRotor, hoverTime, cruiseTime, landTime, distance, -1);
285 }
286 }
287
288 _status.totalDistance = totalHorizontalDistance;
289
290 if (_status.mAhBattery != 0 && _status.batteryChangePoint == -1) {
291 _status.batteryChangePoint = 0;
292 }
293
294 if (linkStartToHome) {
295 // Home position is taken into account for min/max values
296 _minAMSLAltitude = std::fmin(_minAMSLAltitude, settingsItem->plannedHomePositionAltitude()->rawValue().toDouble());
297 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, settingsItem->plannedHomePositionAltitude()->rawValue().toDouble());
298 }
299
300 // Walk the list calculating altitude percentages
301 double altRange = _maxAMSLAltitude - _minAMSLAltitude;
302 for (int i=0; i<visualItems->count(); i++) {
303 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(i));
304
305 if (item->specifiesCoordinate()) {
306 double amslAlt = item->amslEntryAlt();
307 if (altRange == 0.0) {
308 item->setAltPercent(0.0);
309 item->setTerrainPercent(qQNaN());
310 item->setTerrainCollision(false);
311 } else {
312 item->setAltPercent((amslAlt - _minAMSLAltitude) / altRange);
313 double terrainAltitude = item->terrainAltitude();
314 if (qIsNaN(terrainAltitude)) {
315 item->setTerrainPercent(qQNaN());
316 item->setTerrainCollision(false);
317 } else {
318 item->setTerrainPercent((terrainAltitude - _minAMSLAltitude) / altRange);
319 item->setTerrainCollision(amslAlt < terrainAltitude);
320 }
321 }
322 }
323 }
324}
325
326void MissionFlightStatusCalculator::calcPrevWaypointValues(VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
327{
328 QGeoCoordinate currentCoord = currentItem->entryCoordinate();
329 QGeoCoordinate prevCoord = prevItem->exitCoordinate();
330
331 *altDifference = currentItem->amslEntryAlt() - prevItem->amslExitAlt();
332 *distance = prevCoord.distanceTo(currentCoord);
333 *azimuth = prevCoord.azimuthTo(currentCoord);
334}
335
337{
338 QGeoCoordinate currentCoord = currentItem->entryCoordinate();
339 QGeoCoordinate homeCoord = homeItem->exitCoordinate();
340
341 return homeCoord.distanceTo(currentCoord);
342}
343
344void MissionFlightStatusCalculator::_updateBatteryInfo(int waypointIndex)
345{
346 if (_status.mAhBattery != 0) {
347 _status.hoverAmpsTotal = (_status.hoverTime / 60.0) * _status.hoverAmps;
348 _status.cruiseAmpsTotal = (_status.cruiseTime / 60.0) * _status.cruiseAmps;
349 _status.batteriesRequired = ceil((_status.hoverAmpsTotal + _status.cruiseAmpsTotal) / _status.ampMinutesAvailable);
350 if (waypointIndex != -1 && _status.batteriesRequired == 2 && _status.batteryChangePoint == -1) {
351 _status.batteryChangePoint = waypointIndex - 1;
352 }
353 }
354}
355
356void MissionFlightStatusCalculator::_addHoverTime(double hoverTime, double hoverDistance, int waypointIndex)
357{
358 _status.totalTime += hoverTime;
359 _status.hoverTime += hoverTime;
360 _status.hoverDistance += hoverDistance;
361 _status.plannedDistance += hoverDistance;
362 _updateBatteryInfo(waypointIndex);
363}
364
365void MissionFlightStatusCalculator::_addCruiseTime(double cruiseTime, double cruiseDistance, int waypointIndex)
366{
367 _status.totalTime += cruiseTime;
368 _status.cruiseTime += cruiseTime;
369 _status.cruiseDistance += cruiseDistance;
370 _status.plannedDistance += cruiseDistance;
371 _updateBatteryInfo(waypointIndex);
372}
373
374void MissionFlightStatusCalculator::_addTimeDistance(Vehicle* controllerVehicle, bool vtolInHover, double hoverTime, double cruiseTime, double extraTime, double distance, int seqNum)
375{
376 if (controllerVehicle->vtol()) {
377 if (vtolInHover) {
378 _addHoverTime(hoverTime, distance, seqNum);
379 _addHoverTime(extraTime, 0, -1);
380 } else {
381 _addCruiseTime(cruiseTime, distance, seqNum);
382 _addCruiseTime(extraTime, 0, -1);
383 }
384 } else {
385 if (controllerVehicle->multiRotor()) {
386 _addHoverTime(hoverTime, distance, seqNum);
387 _addHoverTime(extraTime, 0, -1);
388 } else {
389 _addCruiseTime(cruiseTime, distance, seqNum);
390 _addCruiseTime(extraTime, 0, -1);
391 }
392 }
393}
Application Settings.
Definition AppSettings.h:9
Fact *offlineEditingAscentSpeed READ offlineEditingAscentSpeed CONSTANT Fact * offlineEditingAscentSpeed()
Fact *offlineEditingDescentSpeed READ offlineEditingDescentSpeed CONSTANT Fact * offlineEditingDescentSpeed()
Fact *batteryPercentRemainingAnnounce READ batteryPercentRemainingAnnounce CONSTANT Fact * batteryPercentRemainingAnnounce()
virtual double minAMSLAltitude(void) const =0
virtual double greatestDistanceTo(const QGeoCoordinate &other) const =0
virtual double complexDistance(void) const =0
virtual double maxAMSLAltitude(void) const =0
virtual void batteryConsumptionData(Vehicle *vehicle, int &mAhBattery, double &hoverAmps, double &cruiseAmps) const
void reset(Vehicle *controllerVehicle, Vehicle *managerVehicle, bool missionContainsVTOLTakeoff)
Resets the flight status fields to defaults based on vehicle properties.
static void calcPrevWaypointValues(VisualMissionItem *currentItem, VisualMissionItem *prevItem, double *azimuth, double *distance, double *altDifference)
void recalc(QmlObjectListModel *visualItems, MissionSettingsItem *settingsItem, Vehicle *controllerVehicle, Vehicle *managerVehicle, AppSettings *appSettings, PlanViewSettings *planViewSettings, bool missionContainsVTOLTakeoff)
static double calcDistanceToHome(VisualMissionItem *currentItem, VisualMissionItem *homeItem)
double param1(void) const
Definition MissionItem.h:54
QGeoCoordinate coordinate(void) const final
Fact *showGimbalOnlyWhenSet READ showGimbalOnlyWhenSet CONSTANT Fact * showGimbalOnlyWhenSet()
QObject * get(int index)
int count() const override final
A SimpleMissionItem is used to represent a single MissionItem to the ui.
QGeoCoordinate entryCoordinate(void) const final
double specifiedVehicleYaw(void) override
MAV_CMD mavCommand(void) const
int command(void) const
MissionItem & missionItem(void)
bool vtol() const
Definition Vehicle.cc:1756
bool multiRotor() const
Definition Vehicle.cc:1751
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
Definition Vehicle.h:442
double defaultHoverSpeed() const
Definition Vehicle.h:523
double defaultCruiseSpeed() const
Definition Vehicle.h:522
void setDistanceFromStart(double distanceFromStart)
virtual int sequenceNumber(void) const =0
void setTerrainCollision(bool terrainCollision)
void setAltDifference(double altDifference)
void setMissionVehicleYaw(double vehicleYaw)
virtual bool isStandaloneCoordinate(void) const =0
virtual double amslExitAlt(void) const =0
virtual double specifiedGimbalPitch(void)=0
void setDistance(double distance)
virtual double specifiedGimbalYaw(void)=0
virtual double specifiedFlightSpeed(void)=0
virtual double amslEntryAlt(void) const =0
void setAltPercent(double altPercent)
void setTerrainPercent(double terrainPercent)
virtual bool isLandCommand(void) const
virtual double additionalTimeDelay(void) const =0
virtual bool specifiesCoordinate(void) const =0
void setAzimuth(double azimuth)
virtual QGeoCoordinate exitCoordinate(void) const =0
virtual void setMissionFlightStatus(MissionFlightStatus_t &missionFlightStatus)
virtual QGeoCoordinate entryCoordinate(void) const =0
double terrainAltitude(void) const
int batteriesRequired
-1 for not supported
double gimbalPitch
NaN signals pitch was never changed.
int mAhBattery
0 for not available
double vehicleSpeed
Either cruise or hover speed based on vehicle type and vtol state.
double ampMinutesAvailable
Amp minutes available from single battery.
double hoverAmps
Amp consumption during hover.
double cruiseAmps
Amp consumption during cruise.
double hoverAmpsTotal
Total hover amps used.
double gimbalYaw
NaN signals yaw was never changed.
double cruiseAmpsTotal
Total cruise amps used.
QGCMAVLinkTypes::VehicleClass_t vtolMode
Either VehicleClassFixedWing, VehicleClassMultiRotor, VehicleClassGeneric (mode unknown)
int batteryChangePoint
-1 for not supported, 0 for not needed