Newer
Older
emit phaseDistanceChanged();
}
}
void WimaController::_setPhaseDuration(double duration)
{
if (!qFuzzyCompare(duration, _phaseDuration)) {
_phaseDuration = duration;
emit phaseDurationChanged();
}
}
bool WimaController::_checkSmartRTLPreCondition(QString &errorString)
{
if (!_localPlanDataValid) {
errorString.append(tr("No WiMA data available. Please define at least a measurement and a service area."));
return false;
}
Vehicle *managerVehicle = masterController()->managerVehicle();
if (!managerVehicle->flying()) {
errorString.append(tr("Vehicle is not flying. Smart RTL not available."));
return false;
}
}
bool WimaController::_calcReturnPath(QString &errorSring)
{
// it is assumed that checkSmartRTLPreCondition() was called first and true was returned
Vehicle *managerVehicle = masterController()->managerVehicle();
QGeoCoordinate currentVehiclePosition = managerVehicle->coordinate();
// check if vehicle inside _joinedArea, this statement is not inside checkSmartRTLPreCondition() because during checkSmartRTLPreCondition() vehicle is not paused yet
if (!_joinedArea.containsCoordinate(currentVehiclePosition)) {
errorSring.append(tr("Vehicle not inside joined area. Action not supported."));
return false;
}
// calculate return path
QVector<QGeoCoordinate> returnPath;
calcShortestPath(currentVehiclePosition, _takeoffLandPostion, returnPath);
// successful?
if (returnPath.isEmpty()) {
errorSring.append(tr("Not able to calculate return path."));
return false;
}
// qWarning() << "returnPath.size()" << returnPath.size();
_saveCurrentMissionItemsToBuffer();
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
1066
1067
1068
1069
1070
1071
1072
1073
1074
1075
1076
1077
1078
1079
1080
1081
1082
1083
// create Mission Items
removeFromVehicle();
QmlObjectListModel* missionControllerVisuals = _missionController->visualItems();
// set homeposition of settingsItem
MissionSettingsItem* settingsItem = missionControllerVisuals->value<MissionSettingsItem *>(0);
if (settingsItem == nullptr) {
qWarning("WimaController: nullptr");
return false;
}
settingsItem->setCoordinate(_takeoffLandPostion);
// copy from returnPath to _missionController
QGeoCoordinate speedItemCoordinate = returnPath.first();
for (auto coordinate : returnPath) {
_missionController->insertSimpleMissionItem(coordinate, missionControllerVisuals->count());
}
//qWarning() << "missionControllerVisuals->count()" << missionControllerVisuals->count();
// create speed item
int speedItemIndex = 1;
_missionController->insertSimpleMissionItem(speedItemCoordinate, speedItemIndex);
SimpleMissionItem *speedItem = missionControllerVisuals->value<SimpleMissionItem*>(speedItemIndex);
if (speedItem == nullptr) {
qWarning("WimaController: nullptr");
return false;
}
speedItem->setCommand(MAV_CMD_DO_CHANGE_SPEED);
speedItem->setCoordinate(speedItemCoordinate);
speedItem->missionItem().setParam2(_arrivalReturnSpeed.rawValue().toDouble());
1086
1087
1088
1089
1090
1091
1092
1093
1094
1095
1096
1097
1098
1099
1100
1101
1102
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
// set second item command to ordinary waypoint (is takeoff)
SimpleMissionItem *secondItem = missionControllerVisuals->value<SimpleMissionItem*>(2);
if (secondItem == nullptr) {
qWarning("WimaController: nullptr");
return false;
}
secondItem->setCoordinate(speedItemCoordinate);
secondItem->setCommand(MAV_CMD_NAV_WAYPOINT);
// set land command for last mission item
SimpleMissionItem *landItem = missionControllerVisuals->value<SimpleMissionItem*>(missionControllerVisuals->count()-1);
if (landItem == nullptr) {
qWarning("WimaController: nullptr");
return false;
}
_missionController->setLandCommand(*landItem);
// copy to _currentMissionItems
//qWarning() << "_currentMissionItems.count()" << _currentMissionItems.count();
for ( int i = 1; i < missionControllerVisuals->count(); i++) {
SimpleMissionItem *visualItem = missionControllerVisuals->value<SimpleMissionItem*>(i);
if (visualItem == nullptr) {
qWarning("WimaController: Nullptr at SimpleMissionItem!");
_currentMissionItems.clear();
return false;
}
SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
_currentMissionItems.append(visualItemCopy);
}
//qWarning() << "_currentMissionItems.count()" << _currentMissionItems.count();
_setPhaseDistance(_phaseDistance + _arrivalPathLength + _returnPathLength);
_setPhaseDuration(_phaseDistance/_flightSpeed.rawValue().toDouble()
+ (_arrivalPathLength + _returnPathLength)
/ _arrivalReturnSpeed.rawValue().toDouble());
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
_missionController->removeAll(); // remove items from _missionController, will be added on upload
updateAltitude();
updateCurrentPath();
emit currentMissionItemsChanged();
//qWarning() << "_currentMissionItems.count()" << _currentMissionItems.count();
_showAllMissionItems.setRawValue(false);
managerVehicle->trajectoryPoints()->clear();
emit uploadAndExecuteConfirmRequired();
return true;
}
void WimaController::_setVehicleHasLowBattery(bool batteryLow)
{
if (_vehicleHasLowBattery != batteryLow) {
_vehicleHasLowBattery = batteryLow;
emit vehicleHasLowBatteryChanged();
}
}
bool WimaController::_executeSmartRTL(QString &errorSring)
{
_executingSmartRTL = true;
connect(masterController()->managerVehicle(), &Vehicle::flyingChanged, this, &WimaController::smartRTLCleanUp);
forceUploadToVehicle();
masterController()->managerVehicle()->startMission();
return true;
}
void WimaController::_loadCurrentMissionItemsFromBuffer()
{
_currentMissionItems.clear();
int numItems = _missionItemsBuffer.count();
for (int i = 0; i < numItems; i++)
_currentMissionItems.append(_missionItemsBuffer.removeAt(0));
updateCurrentPath();
}
void WimaController::_saveCurrentMissionItemsToBuffer()
{
_missionItemsBuffer.clear();
int numCurrentMissionItems = _currentMissionItems.count();
for (int i = 0; i < numCurrentMissionItems; i++)
_missionItemsBuffer.append(_currentMissionItems.removeAt(0));
}