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)
}
}
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();
......
......@@ -55,6 +55,9 @@ public:
/// 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); }
......
......@@ -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;
......
......@@ -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);
}
}
}
......@@ -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);
}
}
......@@ -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)
......@@ -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:
......@@ -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
......
......@@ -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)
......
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