diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index b22974d549b61a26b1564e4cf1edde2c41f30bde..41ca2c67c32c2acfa5b3b9b553e221c3e2107b18 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -748,7 +748,7 @@ void SimpleMissionItem::_setDefaultsForCommand(void) // We default all acceptance radius to 0. This allows flight controller to be in control of // accept radius. _missionItem.setParam2(0); - } else if (uiInfo->isLandCommand() || command == MAV_CMD_DO_SET_ROI_LOCATION) { + } else if ((uiInfo && uiInfo->isLandCommand()) || command == MAV_CMD_DO_SET_ROI_LOCATION) { _altitudeFact.setRawValue(0); _missionItem.setParam7(0); }