Skip to content

Commit

Permalink
Crash fixes and changes for better info (#9073)
Browse files Browse the repository at this point in the history
Rework to prevent crashes from nullptr returns from getUIInfo/getParamInfo
  • Loading branch information
DonLakeFlyer committed Sep 16, 2020
1 parent 48ffa39 commit 28e2918
Show file tree
Hide file tree
Showing 5 changed files with 61 additions and 42 deletions.
16 changes: 16 additions & 0 deletions src/MissionManager/MissionCommandTree.cc
Expand Up @@ -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
{
return _staticCommandTree[QGCMAVLink::FirmwareClassGeneric][QGCMAVLink::VehicleClassGeneric]->commandIds();
Expand Down
3 changes: 3 additions & 0 deletions src/MissionManager/MissionCommandTree.h
Expand Up @@ -55,6 +55,9 @@ class MissionCommandTree : public QGCTool
/// Returns the raw name for the specified command
QString rawName(MAV_CMD command);

bool isLandCommand(MAV_CMD command);
bool isTakeoffCommand(MAV_CMD command);

const QList<MAV_CMD>& allCommandIds(void) const;

Q_INVOKABLE QStringList categoriesForVehicle(Vehicle* vehicle) { return _availableCategoriesForVehicle(vehicle); }
Expand Down
3 changes: 1 addition & 2 deletions src/MissionManager/MissionController.cc
Expand Up @@ -319,8 +319,7 @@ VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordin
_initVisualItem(newItem);

if (newItem->specifiesAltitude()) {
const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, command);
if (!uiInfo->isLandCommand()) {
if (!qgcApp()->toolbox()->missionCommandTree()->isLandCommand(command)) {
double prevAltitude;
int prevAltitudeMode;

Expand Down
77 changes: 40 additions & 37 deletions src/MissionManager/SimpleMissionItem.cc
Expand Up @@ -451,19 +451,21 @@ void SimpleMissionItem::_rebuildTextFieldFacts(void)

const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);

for (int i=1; i<=7; i++) {
bool showUI;
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);

if (showUI && paramInfo && paramInfo->enumStrings().count() == 0 && !paramInfo->nanUnchanged()) {
Fact* paramFact = rgParamFacts[i-1];
FactMetaData* paramMetaData = rgParamMetaData[i-1];

paramFact->_setName(paramInfo->label());
paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
paramMetaData->setRawUnits(paramInfo->units());
paramFact->setMetaData(paramMetaData);
_textFieldFacts.append(paramFact);
if (uiInfo) {
for (int i=1; i<=7; i++) {
bool showUI;
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);

if (showUI && paramInfo && paramInfo->enumStrings().count() == 0 && !paramInfo->nanUnchanged()) {
Fact* paramFact = rgParamFacts[i-1];
FactMetaData* paramMetaData = rgParamMetaData[i-1];

paramFact->_setName(paramInfo->label());
paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
paramMetaData->setRawUnits(paramInfo->units());
paramFact->setMetaData(paramMetaData);
_textFieldFacts.append(paramFact);
}
}
}

Expand All @@ -490,26 +492,28 @@ void SimpleMissionItem::_rebuildNaNFacts(void)

const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);

for (int i=1; i<=7; i++) {
bool showUI;
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);

if (showUI && paramInfo && paramInfo->nanUnchanged()) {
// Show hide Heading field on waypoint based on vehicle yaw to next waypoint setting. This needs to come from the actual vehicle if it exists
// and not _controllerVehicle which is always offline.
Vehicle* firmwareVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
if (!firmwareVehicle) {
firmwareVehicle = _controllerVehicle;
if (uiInfo) {
for (int i=1; i<=7; i++) {
bool showUI;
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);

if (showUI && paramInfo && paramInfo->nanUnchanged()) {
// Show hide Heading field on waypoint based on vehicle yaw to next waypoint setting. This needs to come from the actual vehicle if it exists
// and not _controllerVehicle which is always offline.
Vehicle* firmwareVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
if (!firmwareVehicle) {
firmwareVehicle = _controllerVehicle;
}

Fact* paramFact = rgParamFacts[i-1];
FactMetaData* paramMetaData = rgParamMetaData[i-1];

paramFact->_setName(paramInfo->label());
paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
paramMetaData->setRawUnits(paramInfo->units());
paramFact->setMetaData(paramMetaData);
_nanFacts.append(paramFact);
}

Fact* paramFact = rgParamFacts[i-1];
FactMetaData* paramMetaData = rgParamMetaData[i-1];

paramFact->_setName(paramInfo->label());
paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
paramMetaData->setRawUnits(paramInfo->units());
paramFact->setMetaData(paramMetaData);
_nanFacts.append(paramFact);
}
}

Expand Down Expand Up @@ -778,7 +782,8 @@ void SimpleMissionItem::_sendFriendlyEditAllowedChanged(void)

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)
Expand Down Expand Up @@ -923,7 +928,7 @@ void SimpleMissionItem::applyNewAltitude(double newAltitude)
MAV_CMD command = static_cast<MAV_CMD>(this->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())) {
case MAV_CMD_NAV_LAND:
case MAV_CMD_NAV_VTOL_LAND:
Expand Down Expand Up @@ -989,9 +994,7 @@ void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void)

bool SimpleMissionItem::isLandCommand(void) const
{
MAV_CMD command = static_cast<MAV_CMD>(this->command());
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
return uiInfo->isLandCommand();
return _commandTree->isLandCommand(static_cast<MAV_CMD>(this->command()));
}

QGeoCoordinate SimpleMissionItem::coordinate(void) const
Expand Down
4 changes: 1 addition & 3 deletions src/MissionManager/TakeoffMissionItem.cc
Expand Up @@ -116,9 +116,7 @@ void TakeoffMissionItem::setCoordinate(const QGeoCoordinate& coordinate)

bool TakeoffMissionItem::isTakeoffCommand(MAV_CMD command)
{
const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(qgcApp()->toolbox()->multiVehicleManager()->offlineEditingVehicle(), QGCMAVLink::VehicleClassGeneric, command);

return uiInfo ? uiInfo->isTakeoffCommand() : false;
return qgcApp()->toolbox()->missionCommandTree()->isTakeoffCommand(command);
}

void TakeoffMissionItem::_initLaunchTakeoffAtSameLocation(void)
Expand Down

0 comments on commit 28e2918

Please sign in to comment.