54 bool missionContainsVTOLTakeoff)
56 bool firstCoordinateItem =
true;
59 bool homePositionValid = settingsItem->
coordinate().isValid();
71 _minAMSLAltitude = _maxAMSLAltitude = qQNaN();
73 reset(controllerVehicle, managerVehicle, missionContainsVTOLTakeoff);
75 bool linkStartToHome =
false;
76 bool foundRTL =
false;
77 bool pastLandCommand =
false;
78 double totalHorizontalDistance = 0;
80 for (
int i=0; i<visualItems->
count(); i++) {
85 if (simpleItem && simpleItem->
mavCommand() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
98 switch (simpleItem->
command()) {
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:
124 if (i != 0 && !foundRTL) {
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()) {
135 double azimuth, distance, altDifference;
138 _addHoverTime(takeoffTime, 0, -1);
143 if (!pastLandCommand)
151 _minAMSLAltitude = std::fmin(_minAMSLAltitude, amslAltitude);
152 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, amslAltitude);
157 _minAMSLAltitude = std::fmin(_minAMSLAltitude, complexMinAMSLAltitude);
158 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, complexMaxAMSLAltitude);
162 firstCoordinateItem =
false;
167 if (qIsNaN(newVehicleYaw)) {
169 if (simpleItem != lastFlyThroughVI) {
178 if (lastFlyThroughVI != settingsItem || linkStartToHome) {
180 double azimuth, distance, altDifference;
186 totalHorizontalDistance += distance;
189 if (!pastLandCommand) {
191 double hoverTime = distance / _status.
hoverSpeed;
192 double cruiseTime = distance / _status.
cruiseSpeed;
209 if (!pastLandCommand) {
210 double hoverTime = distance / _status.
hoverSpeed;
211 double cruiseTime = distance / _status.
cruiseSpeed;
215 totalHorizontalDistance += distance;
219 lastFlyThroughVI = item;
227 if (!qIsNaN(newSpeed)) {
230 }
else if (controllerVehicle->
vtol()) {
243 if (simpleItem && controllerVehicle->
vtol()) {
244 switch (simpleItem->
command()) {
245 case MAV_CMD_NAV_TAKEOFF:
246 case MAV_CMD_NAV_VTOL_TAKEOFF:
247 case MAV_CMD_NAV_LAND:
250 case MAV_CMD_NAV_VTOL_LAND:
253 case MAV_CMD_DO_VTOL_TRANSITION:
256 if (transitionState == MAV_VTOL_STATE_MC) {
258 }
else if (transitionState == MAV_VTOL_STATE_FW) {
269 pastLandCommand =
true;
275 if (foundRTL && lastFlyThroughVI != settingsItem && homePositionValid) {
276 double azimuth, distance, altDifference;
279 if (!pastLandCommand) {
281 double hoverTime = distance / _status.
hoverSpeed;
282 double cruiseTime = distance / _status.
cruiseSpeed;
294 if (linkStartToHome) {
296 _minAMSLAltitude = std::fmin(_minAMSLAltitude, settingsItem->plannedHomePositionAltitude()->rawValue().toDouble());
297 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, settingsItem->plannedHomePositionAltitude()->rawValue().toDouble());
301 double altRange = _maxAMSLAltitude - _minAMSLAltitude;
302 for (
int i=0; i<visualItems->
count(); i++) {
307 if (altRange == 0.0) {
312 item->
setAltPercent((amslAlt - _minAMSLAltitude) / altRange);
314 if (qIsNaN(terrainAltitude)) {