Unverified Commit 28e29181 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Crash fixes and changes for better info (#9073)

Rework to prevent crashes from nullptr returns from getUIInfo/getParamInfo
parent 48ffa39e
...@@ -161,6 +161,22 @@ QString MissionCommandTree::rawName(MAV_CMD command) ...@@ -161,6 +161,22 @@ QString MissionCommandTree::rawName(MAV_CMD command)
} }
} }
bool MissionCommandTree::isLandCommand(MAV_CMD command)
{
MissionCommandList * commandList = _staticCommandTree[QGCMAVLink::FirmwareClassGeneric][QGCMAVLink::VehicleClassGeneric];
MissionCommandUIInfo* uiInfo = commandList->getUIInfo(command);
return uiInfo ? uiInfo->isLandCommand() : false;
}
bool MissionCommandTree::isTakeoffCommand(MAV_CMD command)
{
MissionCommandList * commandList = _staticCommandTree[QGCMAVLink::FirmwareClassGeneric][QGCMAVLink::VehicleClassGeneric];
MissionCommandUIInfo* uiInfo = commandList->getUIInfo(command);
return uiInfo ? uiInfo->isTakeoffCommand() : false;
}
const QList<MAV_CMD>& MissionCommandTree::allCommandIds(void) const const QList<MAV_CMD>& MissionCommandTree::allCommandIds(void) const
{ {
return _staticCommandTree[QGCMAVLink::FirmwareClassGeneric][QGCMAVLink::VehicleClassGeneric]->commandIds(); return _staticCommandTree[QGCMAVLink::FirmwareClassGeneric][QGCMAVLink::VehicleClassGeneric]->commandIds();
......
...@@ -55,6 +55,9 @@ public: ...@@ -55,6 +55,9 @@ public:
/// Returns the raw name for the specified command /// Returns the raw name for the specified command
QString rawName(MAV_CMD command); QString rawName(MAV_CMD command);
bool isLandCommand(MAV_CMD command);
bool isTakeoffCommand(MAV_CMD command);
const QList<MAV_CMD>& allCommandIds(void) const; const QList<MAV_CMD>& allCommandIds(void) const;
Q_INVOKABLE QStringList categoriesForVehicle(Vehicle* vehicle) { return _availableCategoriesForVehicle(vehicle); } Q_INVOKABLE QStringList categoriesForVehicle(Vehicle* vehicle) { return _availableCategoriesForVehicle(vehicle); }
......
...@@ -319,8 +319,7 @@ VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordin ...@@ -319,8 +319,7 @@ VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordin
_initVisualItem(newItem); _initVisualItem(newItem);
if (newItem->specifiesAltitude()) { if (newItem->specifiesAltitude()) {
const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, command); if (!qgcApp()->toolbox()->missionCommandTree()->isLandCommand(command)) {
if (!uiInfo->isLandCommand()) {
double prevAltitude; double prevAltitude;
int prevAltitudeMode; int prevAltitudeMode;
......
...@@ -451,6 +451,7 @@ void SimpleMissionItem::_rebuildTextFieldFacts(void) ...@@ -451,6 +451,7 @@ void SimpleMissionItem::_rebuildTextFieldFacts(void)
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
if (uiInfo) {
for (int i=1; i<=7; i++) { for (int i=1; i<=7; i++) {
bool showUI; bool showUI;
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI); const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
...@@ -466,6 +467,7 @@ void SimpleMissionItem::_rebuildTextFieldFacts(void) ...@@ -466,6 +467,7 @@ void SimpleMissionItem::_rebuildTextFieldFacts(void)
_textFieldFacts.append(paramFact); _textFieldFacts.append(paramFact);
} }
} }
}
_ignoreDirtyChangeSignals = false; _ignoreDirtyChangeSignals = false;
} }
...@@ -490,6 +492,7 @@ void SimpleMissionItem::_rebuildNaNFacts(void) ...@@ -490,6 +492,7 @@ void SimpleMissionItem::_rebuildNaNFacts(void)
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
if (uiInfo) {
for (int i=1; i<=7; i++) { for (int i=1; i<=7; i++) {
bool showUI; bool showUI;
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI); const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
...@@ -512,6 +515,7 @@ void SimpleMissionItem::_rebuildNaNFacts(void) ...@@ -512,6 +515,7 @@ void SimpleMissionItem::_rebuildNaNFacts(void)
_nanFacts.append(paramFact); _nanFacts.append(paramFact);
} }
} }
}
_ignoreDirtyChangeSignals = false; _ignoreDirtyChangeSignals = false;
} }
...@@ -778,7 +782,8 @@ void SimpleMissionItem::_sendFriendlyEditAllowedChanged(void) ...@@ -778,7 +782,8 @@ void SimpleMissionItem::_sendFriendlyEditAllowedChanged(void)
QString SimpleMissionItem::category(void) const QString SimpleMissionItem::category(void) const
{ {
return _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, static_cast<MAV_CMD>(command()))->category(); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, static_cast<MAV_CMD>(command()));
return uiInfo ? uiInfo->category() : QString();
} }
void SimpleMissionItem::setCommand(int command) void SimpleMissionItem::setCommand(int command)
...@@ -923,7 +928,7 @@ void SimpleMissionItem::applyNewAltitude(double newAltitude) ...@@ -923,7 +928,7 @@ void SimpleMissionItem::applyNewAltitude(double newAltitude)
MAV_CMD command = static_cast<MAV_CMD>(this->command()); MAV_CMD command = static_cast<MAV_CMD>(this->command());
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
if (uiInfo->specifiesCoordinate() || uiInfo->specifiesAltitudeOnly()) { if (uiInfo && (uiInfo->specifiesCoordinate() || uiInfo->specifiesAltitudeOnly())) {
switch (static_cast<MAV_CMD>(this->command())) { switch (static_cast<MAV_CMD>(this->command())) {
case MAV_CMD_NAV_LAND: case MAV_CMD_NAV_LAND:
case MAV_CMD_NAV_VTOL_LAND: case MAV_CMD_NAV_VTOL_LAND:
...@@ -989,9 +994,7 @@ void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void) ...@@ -989,9 +994,7 @@ void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void)
bool SimpleMissionItem::isLandCommand(void) const bool SimpleMissionItem::isLandCommand(void) const
{ {
MAV_CMD command = static_cast<MAV_CMD>(this->command()); return _commandTree->isLandCommand(static_cast<MAV_CMD>(this->command()));
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
return uiInfo->isLandCommand();
} }
QGeoCoordinate SimpleMissionItem::coordinate(void) const QGeoCoordinate SimpleMissionItem::coordinate(void) const
......
...@@ -116,9 +116,7 @@ void TakeoffMissionItem::setCoordinate(const QGeoCoordinate& coordinate) ...@@ -116,9 +116,7 @@ void TakeoffMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
bool TakeoffMissionItem::isTakeoffCommand(MAV_CMD command) bool TakeoffMissionItem::isTakeoffCommand(MAV_CMD command)
{ {
const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(qgcApp()->toolbox()->multiVehicleManager()->offlineEditingVehicle(), QGCMAVLink::VehicleClassGeneric, command); return qgcApp()->toolbox()->missionCommandTree()->isTakeoffCommand(command);
return uiInfo ? uiInfo->isTakeoffCommand() : false;
} }
void TakeoffMissionItem::_initLaunchTakeoffAtSameLocation(void) void TakeoffMissionItem::_initLaunchTakeoffAtSameLocation(void)
......
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