diff --git a/resources/examples/testfiles/smg/example_smg.nm b/resources/examples/testfiles/smg/example_smg.nm
new file mode 100644
index 000000000..875070051
--- /dev/null
+++ b/resources/examples/testfiles/smg/example_smg.nm
@@ -0,0 +1,32 @@
+// taken from Julia Eisentraut "Value iteration for simple stochastic games: Stopping criterion
+//                              and learning algorithm" - Fig. 1
+
+
+smg
+
+const double p = 2/3;
+
+player maxP
+  [q_action1], [q_action2]
+endplayer
+
+player minP
+  [p_action1]
+endplayer
+
+player sinkstates
+  state_space
+endplayer
+
+
+module state_space
+  s : [0..3];
+
+  [p_action1] s=0 -> (s'=1);
+
+  [q_action1] s=1 -> (s'=0);
+  [q_action2] s=1 -> (1-p) : (s'=1) + (p/2) : (s'=2) + (p/2) : (s'=3);
+
+  [] s=2 -> true;
+  [] s=3 -> true;
+endmodule
diff --git a/src/storm/modelchecker/helper/infinitehorizon/internal/SparseSmgLraHelper.cpp b/src/storm/modelchecker/helper/infinitehorizon/internal/SparseSmgLraHelper.cpp
new file mode 100644
index 000000000..6b8f63739
--- /dev/null
+++ b/src/storm/modelchecker/helper/infinitehorizon/internal/SparseSmgLraHelper.cpp
@@ -0,0 +1,311 @@
+#include "SparseSmgLraHelper.h"
+
+#include "storm/storage/MaximalEndComponent.h"
+#include "storm/storage/StronglyConnectedComponent.h"
+
+#include "storm/utility/graph.h"
+#include "storm/utility/vector.h"
+#include "storm/utility/macros.h"
+#include "storm/utility/SignalHandler.h"
+
+#include "storm/environment/solver/SolverEnvironment.h"
+#include "storm/environment/solver/LongRunAverageSolverEnvironment.h"
+#include "storm/environment/solver/MinMaxSolverEnvironment.h"
+#include "storm/environment/solver/MultiplierEnvironment.h"
+#include "storm/environment/solver/GameSolverEnvironment.h"
+
+#include "modelchecker/helper/infinitehorizon/SparseNondeterministicInfiniteHorizonHelper.h"
+#include "storm/exceptions/UnmetRequirementException.h"
+
+#define SOLVE_MDP 50
+
+namespace storm {
+    namespace modelchecker {
+        namespace helper {
+            namespace internal {
+
+                template <typename ValueType>
+                SparseSmgLraHelper<ValueType>::SparseSmgLraHelper(storm::storage::SparseMatrix<ValueType> const& transitionMatrix, storm::storage::BitVector const statesOfCoalition) : _transitionMatrix(transitionMatrix), _statesOfCoalition(statesOfCoalition) {
+
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType> SparseSmgLraHelper<ValueType>::computeLongRunAverageRewardsSound(Environment const& env, storm::models::sparse::StandardRewardModel<ValueType> const& rewardModel) {
+                    std::vector<ValueType> result;
+                    std::vector<ValueType>  stateRewardsGetter = std::vector<ValueType>(_transitionMatrix.getRowGroupCount(), storm::utility::zero<ValueType>());
+                    if (rewardModel.hasStateRewards()) {
+                        stateRewardsGetter = rewardModel.getStateRewardVector();
+                    }
+                    ValueGetter actionRewardsGetter;
+                    if (rewardModel.hasStateActionRewards() || rewardModel.hasTransitionRewards()) {
+                        if (rewardModel.hasTransitionRewards()) {
+                            actionRewardsGetter = [&] (uint64_t globalChoiceIndex) { return rewardModel.getStateActionAndTransitionReward(globalChoiceIndex, this->_transitionMatrix); };
+                        } else {
+                            actionRewardsGetter = [&] (uint64_t globalChoiceIndex) { return rewardModel.getStateActionReward(globalChoiceIndex); };
+                        }
+                    } else {
+                        actionRewardsGetter = [] (uint64_t) { return storm::utility::zero<ValueType>(); };
+                    }
+                    _b = getBVector(stateRewardsGetter, actionRewardsGetter);
+
+                    // If requested, allocate memory for the choices made
+                    if (this->_produceScheduler) {
+                        if (!this->_producedOptimalChoices.is_initialized()) {
+                            _producedOptimalChoices.emplace();
+                        }
+                        _producedOptimalChoices->resize(_transitionMatrix.getRowGroupCount());
+                    }
+
+                    prepareMultiplier(env, rewardModel);
+                    performValueIteration(env, rewardModel, _b, result);
+
+                    return result;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType> SparseSmgLraHelper<ValueType>::getBVector(std::vector<ValueType> const& stateRewardsGetter, ValueGetter const& actionRewardsGetter) {
+                    std::vector<ValueType> b = std::vector<ValueType>(_transitionMatrix.getRowCount());
+                    size_t globalChoiceCount = 0;
+                    auto rowGroupIndices = _transitionMatrix.getRowGroupIndices();
+                    for (size_t state = 0; state < _transitionMatrix.getRowGroupCount(); state++) {
+                        size_t rowGroupSize = rowGroupIndices[state + 1] - rowGroupIndices[state];
+                        for (size_t choice = 0; choice < rowGroupSize; choice++, globalChoiceCount++)
+                        {
+                            b[globalChoiceCount] = stateRewardsGetter[state] + actionRewardsGetter(globalChoiceCount);
+                        }
+                    }
+                    return b;
+                }
+
+                template <typename ValueType>
+                void SparseSmgLraHelper<ValueType>::performValueIteration(Environment const& env, storm::models::sparse::StandardRewardModel<ValueType> const& rewardModel, std::vector<ValueType> const& b, std::vector<ValueType>& result)
+                {
+                    std::vector<uint64_t> choicesForStrategies = std::vector<uint64_t>(_transitionMatrix.getRowGroupCount(), 0);
+                    auto precision = storm::utility::convertNumber<ValueType>(env.solver().lra().getPrecision());
+
+                    Environment envMinMax = env;
+                    envMinMax.solver().lra().setPrecision(precision / storm::utility::convertNumber<storm::RationalNumber>(2));
+                    do
+                    {
+                        size_t iteration_count = 0;
+                        // Convergent recommender procedure
+
+                        _multiplier->multiplyAndReduce(env, _optimizationDirection, xNew(), &b, xNew(), &choicesForStrategies, &_statesOfCoalition);
+
+                        if (iteration_count % SOLVE_MDP == 0) { // only every 50th iteration
+                            storm::storage::BitVector fixedMaxStrat = getStrategyFixedBitVec(choicesForStrategies, MinMaxStrategy::MaxStrategy);
+                            storm::storage::BitVector fixedMinStrat = getStrategyFixedBitVec(choicesForStrategies, MinMaxStrategy::MinStrategy);
+
+                            // compute bounds
+                            if (fixedMaxStrat != _fixedMaxStrat) {
+                                storm::storage::SparseMatrix<ValueType> restrictedMaxMatrix = _transitionMatrix.restrictRows(fixedMaxStrat);
+
+                                storm::modelchecker::helper::SparseNondeterministicInfiniteHorizonHelper<ValueType> MaxSolver(restrictedMaxMatrix);
+
+                                MaxSolver.setOptimizationDirection(OptimizationDirection::Minimize);
+                                MaxSolver.setProduceChoiceValues(false);
+                                _resultForMax = MaxSolver.computeLongRunAverageRewards(envMinMax, rewardModel);
+                                _fixedMaxStrat = fixedMaxStrat;
+
+                                for (size_t i = 0; i < xNewL().size(); i++) {
+                                    xNewL()[i] = std::max(xNewL()[i], _resultForMax[i]);
+                                }
+                            }
+
+                            if (fixedMinStrat != _fixedMinStrat) {
+                                storm::storage::SparseMatrix<ValueType> restrictedMinMatrix = _transitionMatrix.restrictRows(fixedMinStrat);
+
+                                storm::modelchecker::helper::SparseNondeterministicInfiniteHorizonHelper<ValueType> MinSolver(restrictedMinMatrix);
+                                MinSolver.setOptimizationDirection(OptimizationDirection::Maximize);
+                                MinSolver.setProduceChoiceValues(false);
+                                _resultForMin = MinSolver.computeLongRunAverageRewards(envMinMax, rewardModel);
+                                _fixedMinStrat = fixedMinStrat;
+
+                                for (size_t i = 0; i < xNewU().size(); i++) {
+                                    xNewU()[i] = std::min(xNewU()[i], _resultForMin[i]);
+                                }
+                            }
+                        }
+
+                    } while (!checkConvergence(precision));
+
+                    if (_produceScheduler) {
+                        _multiplier->multiplyAndReduce(env, _optimizationDirection, xNew(), &b, xNew(), &_producedOptimalChoices.get(), &_statesOfCoalition);
+                    }
+
+                    if (_produceChoiceValues) {
+                        if (!this->_choiceValues.is_initialized()) {
+                            this->_choiceValues.emplace();
+                        }
+                        this->_choiceValues->resize(this->_transitionMatrix.getRowCount());
+                        _choiceValues = calcChoiceValues(env, rewardModel);
+                    }
+                    result = xNewL();
+                }
+
+
+                template <typename ValueType>
+                storm::storage::BitVector SparseSmgLraHelper<ValueType>::getStrategyFixedBitVec(std::vector<uint64_t> const& choices, MinMaxStrategy strategy) {
+                    storm::storage::BitVector restrictBy(_transitionMatrix.getRowCount(), true);
+                    auto rowGroupIndices = this->_transitionMatrix.getRowGroupIndices();
+
+                    for(uint state = 0; state < _transitionMatrix.getRowGroupCount(); state++) {
+                        if ((_minimizerStates[state] && strategy == MinMaxStrategy::MaxStrategy) || (!_minimizerStates[state] && strategy == MinMaxStrategy::MinStrategy))
+                            continue;
+
+                        uint rowGroupSize = rowGroupIndices[state + 1] - rowGroupIndices[state];
+                        for(uint rowGroupIndex = 0; rowGroupIndex < rowGroupSize; rowGroupIndex++) {
+                            if ((rowGroupIndex) != choices[state]) {
+                                restrictBy.set(rowGroupIndex + rowGroupIndices[state], false);
+                            }
+                        }
+                    }
+                    return restrictBy;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType> SparseSmgLraHelper<ValueType>::calcChoiceValues(Environment const& env, storm::models::sparse::StandardRewardModel<ValueType> const& rewardModel) {
+                    std::vector<ValueType> choiceValues(_transitionMatrix.getRowCount());
+                    _multiplier->multiply(env, xNewL(), nullptr, choiceValues);
+
+                    return choiceValues;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType> SparseSmgLraHelper<ValueType>::getChoiceValues() const {
+                    STORM_LOG_ASSERT(_produceChoiceValues, "Trying to get the computed choice values although this was not requested.");
+                    STORM_LOG_ASSERT(this->_choiceValues.is_initialized(), "Trying to get the computed choice values but none were available. Was there a computation call before?");
+                    return this->_choiceValues.get();
+                }
+
+                template <typename ValueType>
+                storm::storage::Scheduler<ValueType> SparseSmgLraHelper<ValueType>::extractScheduler() const{
+                    auto const& optimalChoices = getProducedOptimalChoices();
+                    storm::storage::Scheduler<ValueType> scheduler(optimalChoices.size());
+
+                    for (uint64_t state = 0; state < optimalChoices.size(); ++state) {
+                        scheduler.setChoice(optimalChoices[state], state);
+                    }
+
+                    return scheduler;
+                }
+
+                template <typename ValueType>
+                std::vector<uint64_t> const& SparseSmgLraHelper<ValueType>::getProducedOptimalChoices() const {
+                    STORM_LOG_ASSERT(_produceScheduler, "Trying to get the produced optimal choices although no scheduler was requested.");
+                    STORM_LOG_ASSERT(this->_producedOptimalChoices.is_initialized(), "Trying to get the produced optimal choices but none were available. Was there a computation call before?");
+
+                    return this->_producedOptimalChoices.get();
+                }
+
+                template <typename ValueType>
+                void SparseSmgLraHelper<ValueType>::prepareMultiplier(const Environment& env, storm::models::sparse::StandardRewardModel<ValueType> const& rewardModel)
+                {
+                    _multiplier = storm::solver::MultiplierFactory<ValueType>().create(env, _transitionMatrix);
+                    if (_statesOfCoalition.size()) {
+                        _minimizerStates = _optimizationDirection == OptimizationDirection::Maximize ? _statesOfCoalition : ~_statesOfCoalition;
+                    }
+                    else {
+                        _minimizerStates = storm::storage::BitVector(_transitionMatrix.getRowGroupCount(), _optimizationDirection == OptimizationDirection::Minimize);
+                    }
+
+                    _xL = std::vector<ValueType>(_transitionMatrix.getRowGroupCount(), storm::utility::zero<ValueType>());
+                    _x = _xL;
+
+                    _fixedMaxStrat = storm::storage::BitVector(_transitionMatrix.getRowCount(), false);
+                    _fixedMinStrat = storm::storage::BitVector(_transitionMatrix.getRowCount(), false);
+
+                    _resultForMin = std::vector<ValueType>(_transitionMatrix.getRowGroupCount());
+                    _resultForMax = std::vector<ValueType>(_transitionMatrix.getRowGroupCount());
+
+                    _xU = std::vector<ValueType>(_transitionMatrix.getRowGroupCount(), std::numeric_limits<ValueType>::infinity());
+                }
+
+                template <typename ValueType>
+                bool SparseSmgLraHelper<ValueType>::checkConvergence(ValueType threshold) const {
+                    STORM_LOG_ASSERT(_multiplier, "tried to check for convergence without doing an iteration first.");
+                    // Now check whether the currently produced results are precise enough
+                    STORM_LOG_ASSERT(threshold > storm::utility::zero<ValueType>(), "Did not expect a non-positive threshold.");
+                    auto x1It = xNewL().begin();
+                    auto x1Ite = xNewL().end();
+                    auto x2It = xNewU().begin();
+                    for (; x1It != x1Ite; x1It++, x2It++) {
+                        ValueType diff = (*x2It - *x1It);
+                        if (diff > threshold) {
+                            return false;
+                        }
+                    }
+                    return true;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType>& SparseSmgLraHelper<ValueType>::xNewL() {
+                    return _xL;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType> const& SparseSmgLraHelper<ValueType>::xNewL() const {
+                    return _xL;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType>& SparseSmgLraHelper<ValueType>::xNewU() {
+                    return _xU;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType> const& SparseSmgLraHelper<ValueType>::xNewU() const {
+                    return _xU;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType>& SparseSmgLraHelper<ValueType>::xNew() {
+                    return _x;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType> const& SparseSmgLraHelper<ValueType>::xNew() const {
+                    return _x;
+                }
+
+
+                template <typename ValueType>
+                void SparseSmgLraHelper<ValueType>::setRelevantStates(storm::storage::BitVector relevantStates){
+                    _relevantStates = relevantStates;
+                }
+
+                template <typename ValueType>
+                void SparseSmgLraHelper<ValueType>::setValueThreshold(storm::logic::ComparisonType const& comparisonType, const ValueType &thresholdValue) {
+                    _valueThreshold = std::make_pair(comparisonType, thresholdValue);
+                }
+
+                template <typename ValueType>
+                void SparseSmgLraHelper<ValueType>::setOptimizationDirection(storm::solver::OptimizationDirection const& direction) {
+                    _optimizationDirection = direction;
+                }
+
+                template <typename ValueType>
+                void SparseSmgLraHelper<ValueType>::setProduceScheduler(bool value) {
+                    _produceScheduler = value;
+                }
+
+                template <typename ValueType>
+                void SparseSmgLraHelper<ValueType>::setProduceChoiceValues(bool value) {
+                    _produceChoiceValues = value;
+                }
+
+                template <typename ValueType>
+                void SparseSmgLraHelper<ValueType>::setQualitative(bool value) {
+                    _isQualitativeSet = value;
+                }
+
+                template class SparseSmgLraHelper<double>;
+#ifdef STORM_HAVE_CARL
+                template class SparseSmgLraHelper<storm::RationalNumber>;
+#endif
+
+            }
+        }
+    }
+}
+
diff --git a/src/storm/modelchecker/helper/infinitehorizon/internal/SparseSmgLraHelper.h b/src/storm/modelchecker/helper/infinitehorizon/internal/SparseSmgLraHelper.h
new file mode 100644
index 000000000..4a6537945
--- /dev/null
+++ b/src/storm/modelchecker/helper/infinitehorizon/internal/SparseSmgLraHelper.h
@@ -0,0 +1,108 @@
+#pragma once
+
+#include "storm/storage/SparseMatrix.h"
+#include "storm/storage/BitVector.h"
+#include "storm/solver/LinearEquationSolver.h"
+#include "storm/solver/MinMaxLinearEquationSolver.h"
+#include "storm/solver/Multiplier.h"
+#include "storm/logic/ComparisonType.h"
+
+
+namespace storm {
+    class Environment;
+
+
+    namespace modelchecker {
+        namespace helper {
+            namespace internal {
+
+                enum class MinMaxStrategy {
+                MaxStrategy,
+                MinStrategy
+            };
+
+                template <typename ValueType>
+                class SparseSmgLraHelper {
+                public:
+                    // Function mapping from indices to values
+                    typedef std::function<ValueType(uint64_t)> ValueGetter;
+
+                    SparseSmgLraHelper(storm::storage::SparseMatrix<ValueType> const& transitionMatrix, storm::storage::BitVector const statesOfCoalition);
+
+                    void performValueIteration(Environment const& env, storm::models::sparse::StandardRewardModel<ValueType> const& rewardModel, std::vector<ValueType> const& b, std::vector<ValueType>& result);
+
+                    std::vector<ValueType> getChoiceValues() const;
+
+                    storm::storage::Scheduler<ValueType> extractScheduler() const;
+
+                    std::vector<uint64_t> const& getProducedOptimalChoices() const;
+
+                    void prepareMultiplier(const Environment& env, storm::models::sparse::StandardRewardModel<ValueType> const& rewardModel);
+
+                    std::vector<ValueType> computeLongRunAverageRewardsSound(Environment const& env, storm::models::sparse::StandardRewardModel<ValueType> const& rewardModel);
+
+                    void setRelevantStates(storm::storage::BitVector relevantStates);
+
+                    void setValueThreshold(storm::logic::ComparisonType const& comparisonType, ValueType const& thresholdValue);
+
+                    void setOptimizationDirection(storm::solver::OptimizationDirection const& direction);
+
+                    void setProduceScheduler(bool value);
+
+                    void setProduceChoiceValues(bool value);
+
+                    void setQualitative(bool value);
+
+                private:
+
+                    bool checkConvergence(ValueType threshold) const;
+
+                    storm::storage::BitVector getStrategyFixedBitVec(std::vector<uint64_t> const& choices, MinMaxStrategy strategy);
+
+                    std::vector<ValueType> getBVector(std::vector<ValueType> const& stateRewardsGetter, ValueGetter const& actionRewardsGetter);
+
+                    std::vector<ValueType> calcChoiceValues(Environment const& env, storm::models::sparse::StandardRewardModel<ValueType> const& rewardModel);
+
+                    std::vector<ValueType>& xNew();
+                    std::vector<ValueType> const& xNew() const;
+
+                    std::vector<ValueType>& xNewL();
+                    std::vector<ValueType> const& xNewL() const;
+
+                    std::vector<ValueType>& xNewU();
+                    std::vector<ValueType> const& xNewU() const;
+
+                    storm::storage::SparseMatrix<ValueType> const& _transitionMatrix;
+                    storm::storage::BitVector const _statesOfCoalition;
+
+                    storm::storage::BitVector _relevantStates;
+                    storm::storage::BitVector _minimizerStates;
+
+                    storm::storage::BitVector _fixedMinStrat;
+                    storm::storage::BitVector _fixedMaxStrat;
+                    std::vector<ValueType> _resultForMax;
+                    std::vector<ValueType> _resultForMin;
+
+                    std::vector<ValueType> _b;
+
+                    boost::optional<std::pair<storm::logic::ComparisonType, ValueType>> _valueThreshold;
+                    storm::solver::OptimizationDirection _optimizationDirection;
+                    bool _produceScheduler;
+                    bool _produceChoiceValues;
+                    bool _isQualitativeSet;
+
+                    std::vector<ValueType> _x, _xL, _xU;
+                    std::vector<ValueType> _Tsx1, _Tsx2, _TsChoiceValues;
+                    std::vector<ValueType> _Isx, _Isb, _IsChoiceValues;
+                    std::unique_ptr<storm::solver::Multiplier<ValueType>> _multiplier;
+                    std::unique_ptr<storm::solver::MinMaxLinearEquationSolver<ValueType>> _Solver;
+                    std::unique_ptr<storm::solver::LinearEquationSolver<ValueType>> _DetIsSolver;
+                    std::unique_ptr<storm::Environment> _IsSolverEnv;
+
+                    boost::optional<std::vector<uint64_t>> _producedOptimalChoices;
+                    boost::optional<std::vector<ValueType>> _choiceValues;
+                };
+            }
+        }
+    }
+}
diff --git a/src/storm/modelchecker/rpatl/SparseSmgRpatlModelChecker.cpp b/src/storm/modelchecker/rpatl/SparseSmgRpatlModelChecker.cpp
index 79cc6fc87..754ca74b2 100644
--- a/src/storm/modelchecker/rpatl/SparseSmgRpatlModelChecker.cpp
+++ b/src/storm/modelchecker/rpatl/SparseSmgRpatlModelChecker.cpp
@@ -14,6 +14,8 @@
 
 #include "storm/modelchecker/rpatl/helper/SparseSmgRpatlHelper.h"
 #include "storm/modelchecker/helper/infinitehorizon/SparseNondeterministicGameInfiniteHorizonHelper.h"
+#include "storm/modelchecker/helper/infinitehorizon/internal/SparseSmgLraHelper.h"
+
 #include "storm/modelchecker/helper/utility/SetInformationFromCheckTask.h"
 
 #include "storm/logic/FragmentSpecification.h"
@@ -141,8 +143,29 @@ namespace storm {
             ExplicitQualitativeCheckResult const& leftResult = leftResultPointer->asExplicitQualitativeCheckResult();
             ExplicitQualitativeCheckResult const& rightResult = rightResultPointer->asExplicitQualitativeCheckResult();
 
+            if (env.solver().isForceSoundness()) {
+                auto ret = storm::modelchecker::helper::SparseSmgRpatlHelper<ValueType>::computeUntilProbabilitiesSound(
+                    env, storm::solver::SolveGoal<ValueType>(this->getModel(), checkTask), this->getModel().getTransitionMatrix(),
+                    this->getModel().getBackwardTransitions(), leftResult.getTruthValuesVector(), rightResult.getTruthValuesVector(),
+                    checkTask.isQualitativeSet(), statesOfCoalition, checkTask.isProduceSchedulersSet(), checkTask.getHint());
+
+                std::unique_ptr<CheckResult> result(new ExplicitQuantitativeCheckResult<ValueType>(std::move(ret.values)));
+                if(checkTask.isShieldingTask()) {
+                    storm::storage::BitVector allStatesBv = storm::storage::BitVector(this->getModel().getTransitionMatrix().getRowGroupCount(), true);
+                    auto shield = tempest::shields::createShield<ValueType>(std::make_shared<storm::models::sparse::Smg<ValueType>>(this->getModel()), std::move(ret.choiceValues), checkTask.getShieldingExpression(), checkTask.getOptimizationDirection(), allStatesBv, ~statesOfCoalition);
+                    result->asExplicitQuantitativeCheckResult<ValueType>().setShield(std::move(shield));
+                }
+                if (checkTask.isProduceSchedulersSet() && ret.scheduler) {
+                    result->asExplicitQuantitativeCheckResult<ValueType>().setScheduler(std::move(ret.scheduler));
+                }
+                return result;
+            }
 
-            auto ret = storm::modelchecker::helper::SparseSmgRpatlHelper<ValueType>::computeUntilProbabilities(env, storm::solver::SolveGoal<ValueType>(this->getModel(), checkTask), this->getModel().getTransitionMatrix(), this->getModel().getBackwardTransitions(), leftResult.getTruthValuesVector(), rightResult.getTruthValuesVector(), checkTask.isQualitativeSet(), statesOfCoalition, checkTask.isProduceSchedulersSet(), checkTask.getHint());
+            auto ret = storm::modelchecker::helper::SparseSmgRpatlHelper<ValueType>::computeUntilProbabilities(
+                    env, storm::solver::SolveGoal<ValueType>(this->getModel(), checkTask), this->getModel().getTransitionMatrix(),
+                    this->getModel().getBackwardTransitions(), leftResult.getTruthValuesVector(), rightResult.getTruthValuesVector(),
+                    checkTask.isQualitativeSet(), statesOfCoalition, checkTask.isProduceSchedulersSet(), checkTask.getHint());
+            STORM_LOG_DEBUG(ret.values);
             std::unique_ptr<CheckResult> result(new ExplicitQuantitativeCheckResult<ValueType>(std::move(ret.values)));
             if(checkTask.isShieldingTask()) {
                 storm::storage::BitVector allStatesBv = storm::storage::BitVector(this->getModel().getTransitionMatrix().getRowGroupCount(), true);
@@ -239,10 +262,27 @@ namespace storm {
         template<typename SparseSmgModelType>
         std::unique_ptr<CheckResult> SparseSmgRpatlModelChecker<SparseSmgModelType>::computeLongRunAverageRewards(Environment const& env, storm::logic::RewardMeasureType rewardMeasureType, CheckTask<storm::logic::LongRunAverageRewardFormula, ValueType> const& checkTask) {
             auto rewardModel = storm::utility::createFilteredRewardModel(this->getModel(), checkTask);
+
+            if (env.solver().isForceSoundness()) {
+                storm::modelchecker::helper::internal::SparseSmgLraHelper<ValueType> helper(this->getModel().getTransitionMatrix(), statesOfCoalition);
+                storm::modelchecker::helper::setInformationFromCheckTaskNondeterministic(helper, checkTask, this->getModel());
+                auto values = helper.computeLongRunAverageRewardsSound(env, rewardModel.get());
+                std::unique_ptr<CheckResult> result(new ExplicitQuantitativeCheckResult<ValueType>(std::move(values)));
+
+                if(checkTask.isShieldingTask()) {
+                    storm::storage::BitVector allStatesBv = storm::storage::BitVector(this->getModel().getTransitionMatrix().getRowGroupCount(), true);
+                    auto shield = tempest::shields::createQuantitativeShield<ValueType>(std::make_shared<storm::models::sparse::Smg<ValueType>>(this->getModel()), helper.getChoiceValues(), checkTask.getShieldingExpression(), checkTask.getOptimizationDirection(), allStatesBv, statesOfCoalition);
+                    result->asExplicitQuantitativeCheckResult<ValueType>().setShield(std::move(shield));
+                }
+                if (checkTask.isProduceSchedulersSet()) {
+                    result->asExplicitQuantitativeCheckResult<ValueType>().setScheduler(std::make_unique<storm::storage::Scheduler<ValueType>>(helper.extractScheduler()));
+                }
+                return result;
+            }
+
             storm::modelchecker::helper::SparseNondeterministicGameInfiniteHorizonHelper<ValueType> helper(this->getModel().getTransitionMatrix(), statesOfCoalition);
             storm::modelchecker::helper::setInformationFromCheckTaskNondeterministic(helper, checkTask, this->getModel());
             auto values = helper.computeLongRunAverageRewards(env, rewardModel.get());
-
             std::unique_ptr<CheckResult> result(new ExplicitQuantitativeCheckResult<ValueType>(std::move(values)));
             if(checkTask.isShieldingTask()) {
                 storm::storage::BitVector allStatesBv = storm::storage::BitVector(this->getModel().getTransitionMatrix().getRowGroupCount(), true);
diff --git a/src/storm/modelchecker/rpatl/helper/SparseSmgRpatlHelper.cpp b/src/storm/modelchecker/rpatl/helper/SparseSmgRpatlHelper.cpp
index 31ddac9da..e2a349a50 100644
--- a/src/storm/modelchecker/rpatl/helper/SparseSmgRpatlHelper.cpp
+++ b/src/storm/modelchecker/rpatl/helper/SparseSmgRpatlHelper.cpp
@@ -9,6 +9,7 @@
 #include "storm/utility/vector.h"
 #include "storm/utility/graph.h"
 #include "storm/modelchecker/rpatl/helper/internal/GameViHelper.h"
+#include "storm/modelchecker/rpatl/helper/internal/SoundGameViHelper.h"
 
 namespace storm {
     namespace modelchecker {
@@ -21,8 +22,7 @@ namespace storm {
 
                 // Relevant states are those states which are phiStates and not PsiStates.
                 storm::storage::BitVector relevantStates = phiStates & ~psiStates;
-
-                // Initialize the x vector and solution vector result.
+                    // Initialize the x vector and solution vector result.
                 std::vector<ValueType> x = std::vector<ValueType>(relevantStates.getNumberOfSetBits(), storm::utility::zero<ValueType>());
                 std::vector<ValueType> result = std::vector<ValueType>(transitionMatrix.getRowGroupCount(), storm::utility::zero<ValueType>());
                 std::vector<ValueType> b = transitionMatrix.getConstrainedRowGroupSumVector(relevantStates, psiStates);
@@ -60,7 +60,80 @@ namespace storm {
             }
 
             template<typename ValueType>
-            storm::storage::Scheduler<ValueType> SparseSmgRpatlHelper<ValueType>::expandScheduler(storm::storage::Scheduler<ValueType> scheduler, storm::storage::BitVector psiStates, storm::storage::BitVector notPhiStates) {
+            SMGSparseModelCheckingHelperReturnType<ValueType> SparseSmgRpatlHelper<ValueType>::computeUntilProbabilitiesSound(Environment const& env, storm::solver::SolveGoal<ValueType>&& goal, storm::storage::SparseMatrix<ValueType> const& transitionMatrix, storm::storage::SparseMatrix<ValueType> const& backwardTransitions, storm::storage::BitVector const& phiStates, storm::storage::BitVector const& psiStates, bool qualitative, storm::storage::BitVector statesOfCoalition, bool produceScheduler, ModelCheckerHint const& hint) {
+                storm::storage::BitVector probGreater0 = storm::utility::graph::performProbGreater0(backwardTransitions, phiStates, psiStates);
+                std::unique_ptr<storm::storage::Scheduler<ValueType>> scheduler;
+                storm::storage::BitVector relevantStates = phiStates;
+
+                // Initialize the x vector and solution vector result.
+                std::vector<ValueType> xL = std::vector<ValueType>(transitionMatrix.getRowGroupCount(), storm::utility::zero<ValueType>());
+                // assigning 1s to the xL vector for all Goal states
+                auto xL_begin = xL.begin();
+                std::for_each(xL.begin(), xL.end(), [&psiStates, &xL_begin](ValueType &it)
+                              {
+                                  if (psiStates[&it - &(*xL_begin)])
+                                      it = 1;
+                              });
+                size_t i = 0;
+                auto new_end = std::remove_if(xL.begin(), xL.end(), [&relevantStates, &i](const auto& item) {
+                    bool ret = !(relevantStates[i]);
+                    i++;
+                    return ret;
+                });
+                xL.erase(new_end, xL.end());
+                xL.resize(relevantStates.getNumberOfSetBits());
+                std::vector<ValueType> xU = std::vector<ValueType>(transitionMatrix.getRowGroupCount(), storm::utility::zero<ValueType>());
+                // assigning 1s to the xU vector for all states except the states s where Prob(sEf) = 0 for all goal states f
+                auto xU_begin = xU.begin();
+                std::for_each(xU.begin(), xU.end(), [&probGreater0, &xU_begin](ValueType &it)
+                              {
+                                  if (probGreater0[&it - &(*xU_begin)])
+                                      it = 1;
+                              });
+                i = 0;
+                auto new_end_U = std::remove_if(xU.begin(), xU.end(), [&relevantStates, &i](const auto& item) {
+                    bool ret = !(relevantStates[i]);
+                    i++;
+                    return ret;
+                });
+                xU.erase(new_end_U, xU.end());
+                xU.resize(relevantStates.getNumberOfSetBits());
+
+                storm::storage::BitVector clippedPsiStates(relevantStates.getNumberOfSetBits());
+                clippedPsiStates.setClippedStatesOfCoalition(relevantStates, psiStates);
+
+                std::vector<ValueType> b = transitionMatrix.getConstrainedRowGroupSumVector(relevantStates, psiStates);
+                std::vector<ValueType> result = std::vector<ValueType>(transitionMatrix.getRowGroupCount(), storm::utility::zero<ValueType>());
+
+                storm::storage::BitVector clippedStatesOfCoalition(relevantStates.getNumberOfSetBits());
+                clippedStatesOfCoalition.setClippedStatesOfCoalition(relevantStates, statesOfCoalition);
+                std::vector<ValueType> constrainedChoiceValues = std::vector<ValueType>(b.size(), storm::utility::zero<ValueType>());
+
+                if (!relevantStates.empty()) {
+                    storm::storage::SparseMatrix<ValueType> submatrix = transitionMatrix.getSubmatrix(true, relevantStates, relevantStates, false);
+                    storm::modelchecker::helper::internal::SoundGameViHelper<ValueType> viHelper(submatrix, submatrix.transpose(), b, clippedStatesOfCoalition,
+                                                                                                 clippedPsiStates, goal.direction());
+
+                    if (produceScheduler) {
+                        viHelper.setProduceScheduler(true);
+                    }
+
+                    viHelper.performValueIteration(env, xL, xU, goal.direction(), constrainedChoiceValues);
+
+                    viHelper.fillChoiceValuesVector(constrainedChoiceValues, relevantStates, transitionMatrix.getRowGroupIndices());
+                    storm::utility::vector::setVectorValues(result, relevantStates, xL);
+
+                    if (produceScheduler) {
+                        scheduler =
+                            std::make_unique<storm::storage::Scheduler<ValueType>>(expandScheduler(viHelper.extractScheduler(), psiStates, ~phiStates, true));
+                    }
+                }
+
+                return SMGSparseModelCheckingHelperReturnType<ValueType>(std::move(result), std::move(relevantStates), std::move(scheduler), std::move(constrainedChoiceValues));
+            }
+
+            template<typename ValueType>
+            storm::storage::Scheduler<ValueType> SparseSmgRpatlHelper<ValueType>::expandScheduler(storm::storage::Scheduler<ValueType> scheduler, storm::storage::BitVector psiStates, storm::storage::BitVector notPhiStates, bool sound) {
                 storm::storage::Scheduler<ValueType> completeScheduler(psiStates.size());
                 uint_fast64_t maybeStatesCounter = 0;
                 uint schedulerSize = psiStates.size();
@@ -68,6 +141,9 @@ namespace storm {
                     // psiStates already fulfill formulae so we can set an arbitrary action
                     if(psiStates.get(stateCounter)) {
                         completeScheduler.setChoice(0, stateCounter);
+                        if (sound) {
+                            maybeStatesCounter++;
+                        }
                     // ~phiStates do not fulfill formulae so we can set an arbitrary action
                     } else if(notPhiStates.get(stateCounter)) {
                         completeScheduler.setChoice(0, stateCounter);
@@ -86,7 +162,22 @@ namespace storm {
                 storm::storage::BitVector notPsiStates = ~psiStates;
                 statesOfCoalition.complement();
 
-                auto result = computeUntilProbabilities(env, std::move(goal), transitionMatrix, backwardTransitions, storm::storage::BitVector(transitionMatrix.getRowGroupCount(), true), notPsiStates, qualitative, statesOfCoalition, produceScheduler, hint);
+                if (env.solver().isForceSoundness()) {
+                    auto result = computeUntilProbabilitiesSound(env, std::move(goal), transitionMatrix, backwardTransitions,
+                                                                 storm::storage::BitVector(transitionMatrix.getRowGroupCount(), true), notPsiStates,
+                                                                 qualitative, statesOfCoalition, produceScheduler, hint);
+                    for (auto& element : result.values) {
+                        element = storm::utility::one<ValueType>() - element;
+                    }
+                    for (auto& element : result.choiceValues) {
+                        element = storm::utility::one<ValueType>() - element;
+                    }
+                    return result;
+                }
+
+                auto result = computeUntilProbabilities(env, std::move(goal), transitionMatrix, backwardTransitions,
+                                                             storm::storage::BitVector(transitionMatrix.getRowGroupCount(), true), notPsiStates,
+                                                             qualitative, statesOfCoalition, produceScheduler, hint);
                 for (auto& element : result.values) {
                     element = storm::utility::one<ValueType>() - element;
                 }
diff --git a/src/storm/modelchecker/rpatl/helper/SparseSmgRpatlHelper.h b/src/storm/modelchecker/rpatl/helper/SparseSmgRpatlHelper.h
index 0592c929b..c0216d23f 100644
--- a/src/storm/modelchecker/rpatl/helper/SparseSmgRpatlHelper.h
+++ b/src/storm/modelchecker/rpatl/helper/SparseSmgRpatlHelper.h
@@ -35,12 +35,13 @@ namespace storm {
             class SparseSmgRpatlHelper {
             public:
                 static SMGSparseModelCheckingHelperReturnType<ValueType> computeUntilProbabilities(Environment const& env, storm::solver::SolveGoal<ValueType>&& goal, storm::storage::SparseMatrix<ValueType> const& transitionMatrix, storm::storage::SparseMatrix<ValueType> const& backwardTransitions, storm::storage::BitVector const& phiStates, storm::storage::BitVector const& psiStates, bool qualitative, storm::storage::BitVector statesOfCoalition, bool produceScheduler, ModelCheckerHint const& hint = ModelCheckerHint());
+                static SMGSparseModelCheckingHelperReturnType<ValueType> computeUntilProbabilitiesSound(Environment const& env, storm::solver::SolveGoal<ValueType>&& goal, storm::storage::SparseMatrix<ValueType> const& transitionMatrix, storm::storage::SparseMatrix<ValueType> const& backwardTransitions, storm::storage::BitVector const& phiStates, storm::storage::BitVector const& psiStates, bool qualitative, storm::storage::BitVector statesOfCoalition, bool produceScheduler, ModelCheckerHint const& hint);
                 static SMGSparseModelCheckingHelperReturnType<ValueType> computeGloballyProbabilities(Environment const& env, storm::solver::SolveGoal<ValueType>&& goal, storm::storage::SparseMatrix<ValueType> const& transitionMatrix, storm::storage::SparseMatrix<ValueType> const& backwardTransitions, storm::storage::BitVector const& psiStates, bool qualitative, storm::storage::BitVector statesOfCoalition, bool produceScheduler, ModelCheckerHint const& hint = ModelCheckerHint());
                 static SMGSparseModelCheckingHelperReturnType<ValueType> computeNextProbabilities(Environment const& env, storm::solver::SolveGoal<ValueType>&& goal, storm::storage::SparseMatrix<ValueType> const& transitionMatrix, storm::storage::SparseMatrix<ValueType> const& backwardTransitions, storm::storage::BitVector const& psiStates, bool qualitative, storm::storage::BitVector statesOfCoalition, bool produceScheduler, ModelCheckerHint const& hint);
                 static SMGSparseModelCheckingHelperReturnType<ValueType> computeBoundedGloballyProbabilities(Environment const& env, storm::solver::SolveGoal<ValueType>&& goal, storm::storage::SparseMatrix<ValueType> const& transitionMatrix, storm::storage::SparseMatrix<ValueType> const& backwardTransitions, storm::storage::BitVector const& psiStates, bool qualitative, storm::storage::BitVector statesOfCoalition, bool produceScheduler, ModelCheckerHint const& hint, uint64_t lowerBound, uint64_t upperBound);
                 static SMGSparseModelCheckingHelperReturnType<ValueType> computeBoundedUntilProbabilities(Environment const& env, storm::solver::SolveGoal<ValueType>&& goal, storm::storage::SparseMatrix<ValueType> const& transitionMatrix, storm::storage::SparseMatrix<ValueType> const& backwardTransitions, storm::storage::BitVector const& phiStates, storm::storage::BitVector const& psiStates, bool qualitative, storm::storage::BitVector statesOfCoalition, bool produceScheduler, ModelCheckerHint const& hint, uint64_t lowerBound, uint64_t upperBound, bool computeBoundedGlobally = false);
             private:
-                static storm::storage::Scheduler<ValueType> expandScheduler(storm::storage::Scheduler<ValueType> scheduler, storm::storage::BitVector psiStates, storm::storage::BitVector notPhiStates);
+                static storm::storage::Scheduler<ValueType> expandScheduler(storm::storage::Scheduler<ValueType> scheduler, storm::storage::BitVector psiStates, storm::storage::BitVector notPhiStates, bool sound = false);
                 static void expandChoiceValues(std::vector<uint_fast64_t> const& rowGroupIndices, storm::storage::BitVector const& relevantStates, std::vector<ValueType> const& constrainedChoiceValues, std::vector<ValueType>& choiceValues);
             };
         }
diff --git a/src/storm/modelchecker/rpatl/helper/internal/SoundGameViHelper.cpp b/src/storm/modelchecker/rpatl/helper/internal/SoundGameViHelper.cpp
new file mode 100644
index 000000000..aab2935d6
--- /dev/null
+++ b/src/storm/modelchecker/rpatl/helper/internal/SoundGameViHelper.cpp
@@ -0,0 +1,371 @@
+#include "SoundGameViHelper.h"
+
+#include "storm/environment/Environment.h"
+#include "storm/environment/solver/SolverEnvironment.h"
+#include "storm/environment/solver/GameSolverEnvironment.h"
+
+
+#include "storm/utility/SignalHandler.h"
+#include "storm/utility/vector.h"
+
+namespace storm {
+    namespace modelchecker {
+        namespace helper {
+            namespace internal {
+
+                template <typename ValueType>
+                SoundGameViHelper<ValueType>::SoundGameViHelper(storm::storage::SparseMatrix<ValueType> const& transitionMatrix, storm::storage::SparseMatrix<ValueType> const& backwardTransitions, std::vector<ValueType> b, storm::storage::BitVector statesOfCoalition, storm::storage::BitVector psiStates, OptimizationDirection const& optimizationDirection) : _transitionMatrix(transitionMatrix), _backwardTransitions(backwardTransitions), _statesOfCoalition(statesOfCoalition), _psiStates(psiStates), _optimizationDirection(optimizationDirection), _b(b) {
+                    // Intentionally left empty.
+                }
+
+                template <typename ValueType>
+                void SoundGameViHelper<ValueType>::prepareSolversAndMultipliers(const Environment& env) {
+                    _multiplier = storm::solver::MultiplierFactory<ValueType>().create(env, _transitionMatrix);
+                    _x1IsCurrent = false;
+                    if (_statesOfCoalition.size()) {
+                        _minimizerStates = _optimizationDirection == OptimizationDirection::Maximize ? _statesOfCoalition : ~_statesOfCoalition;
+                    }
+                    else {
+                        _minimizerStates = storm::storage::BitVector(_transitionMatrix.getRowGroupCount(), _optimizationDirection == OptimizationDirection::Minimize);
+                    }
+                    _oldPolicy = storm::storage::BitVector(_transitionMatrix.getRowCount(), false);
+                    _timing = std::vector<double>(5, 0);
+                }
+
+                template <typename ValueType>
+                void SoundGameViHelper<ValueType>::performValueIteration(Environment const& env, std::vector<ValueType>& xL, std::vector<ValueType>& xU, storm::solver::OptimizationDirection const dir, std::vector<ValueType>& constrainedChoiceValues) {
+
+                    prepareSolversAndMultipliers(env);
+                    // Get precision for convergence check.
+                    ValueType precision = storm::utility::convertNumber<ValueType>(env.solver().game().getPrecision());
+
+                    uint64_t maxIter = env.solver().game().getMaximalNumberOfIterations();
+                    _x1L = xL;
+                    _x2L = _x1L;
+
+                    _x1U = xU;
+                    _x2U = _x1U;
+
+                    if (this->isProduceSchedulerSet()) {
+                        if (!this->_producedOptimalChoices.is_initialized()) {
+                            this->_producedOptimalChoices.emplace();
+                        }
+                        this->_producedOptimalChoices->resize(this->_transitionMatrix.getRowGroupCount());
+                    }
+
+                    uint64_t iter = 0;
+                    constrainedChoiceValues = std::vector<ValueType>(_transitionMatrix.getRowCount(), storm::utility::zero<ValueType>());
+
+                    while (iter < maxIter) {
+                        performIterationStep(env, dir);
+                        if (checkConvergence(precision)) {
+                            // one last iteration for shield
+                            _multiplier->multiply(env, xNewL(), nullptr, constrainedChoiceValues);
+                            storm::storage::BitVector psiStates = _psiStates;
+                            auto xL_begin = xNewL().begin();
+                            std::for_each(xNewL().begin(), xNewL().end(), [&psiStates, &xL_begin](ValueType &it){
+                                 if (psiStates[&it - &(*xL_begin)])
+                                        it = 1;
+                            });
+                            break;
+                        }
+                        if (storm::utility::resources::isTerminate()) {
+                            break;
+                        }
+                        ++iter;
+                    }
+                    xL = xNewL();
+                    xU = xNewU();
+
+                     if (isProduceSchedulerSet()) {
+                        // We will be doing one more iteration step and track scheduler choices this time.
+                        _x1IsCurrent = !_x1IsCurrent;
+                        _multiplier->multiplyAndReduce(env, dir, xOldL(), nullptr, xNewL(), &_producedOptimalChoices.get(), &_statesOfCoalition);
+                        storm::storage::BitVector psiStates = _psiStates;
+                        auto xL_begin = xNewL().begin();
+                        std::for_each(xNewL().begin(), xNewL().end(), [&psiStates, &xL_begin](ValueType &it)
+                                      {
+                                          if (psiStates[&it - &(*xL_begin)])
+                                              it = 1;
+                                      });
+                    }
+                }
+
+                template <typename ValueType>
+                void SoundGameViHelper<ValueType>::performIterationStep(Environment const& env, storm::solver::OptimizationDirection const dir, std::vector<uint64_t>* choices) {
+                    storm::storage::BitVector reducedMinimizerActions = {storm::storage::BitVector(this->_transitionMatrix.getRowCount(), true)};
+
+                    // under approximation
+                    if (!_multiplier) {
+                        prepareSolversAndMultipliers(env);
+                    }
+                    _x1IsCurrent = !_x1IsCurrent;
+                    std::vector<ValueType> choiceValuesL = std::vector<ValueType>(this->_transitionMatrix.getRowCount(), storm::utility::zero<ValueType>());
+
+                    _multiplier->multiply(env, xOldL(), nullptr, choiceValuesL);
+                    reduceChoiceValues(choiceValuesL, &reducedMinimizerActions, xNewL());
+                    storm::storage::BitVector psiStates = _psiStates;
+                    auto xL_begin = xNewL().begin();
+                    std::for_each(xNewL().begin(), xNewL().end(), [&psiStates, &xL_begin](ValueType &it)
+                                  {
+                                      if (psiStates[&it - &(*xL_begin)])
+                                          it = 1;
+                                  });
+
+                    // over_approximation
+                    std::vector<ValueType> choiceValuesU = std::vector<ValueType>(this->_transitionMatrix.getRowCount(), storm::utility::zero<ValueType>());
+
+                    _multiplier->multiply(env, xOldU(), nullptr, choiceValuesU);
+                    reduceChoiceValues(choiceValuesU, nullptr, xNewU());
+                    auto xU_begin = xNewU().begin();
+                    std::for_each(xNewU().begin(), xNewU().end(), [&psiStates, &xU_begin](ValueType &it)
+                                  {
+                                      if (psiStates[&it - &(*xU_begin)])
+                                          it = 1;
+                                  });
+
+                    if (reducedMinimizerActions != _oldPolicy) { // new MECs only if Policy changed
+                        // restricting the none optimal minimizer choices
+                        _restrictedTransitions = this->_transitionMatrix.restrictRows(reducedMinimizerActions);
+
+                        // find_MSECs()
+                        _MSECs = storm::storage::MaximalEndComponentDecomposition<ValueType>(_restrictedTransitions, _restrictedTransitions.transpose(true));
+                    }
+
+                    // reducing the choiceValuesU
+                    size_t i = 0;
+                    auto new_end = std::remove_if(choiceValuesU.begin(), choiceValuesU.end(), [&reducedMinimizerActions, &i](const auto& item) {
+                        bool ret = !(reducedMinimizerActions[i]);
+                        i++;
+                        return ret;
+                    });
+                    choiceValuesU.erase(new_end, choiceValuesU.end());
+
+                    _oldPolicy = reducedMinimizerActions;
+
+                    // deflating the MSECs
+                    deflate(_MSECs, _restrictedTransitions, xNewU(), choiceValuesU);
+                }
+
+                template <typename ValueType>
+                void SoundGameViHelper<ValueType>::deflate(storm::storage::MaximalEndComponentDecomposition<ValueType> const MSEC, storage::SparseMatrix<ValueType> const restrictedMatrix,  std::vector<ValueType>& xU, std::vector<ValueType> choiceValues) {
+
+                    auto rowGroupIndices = restrictedMatrix.getRowGroupIndices();
+                    auto choice_begin = choiceValues.begin();
+                    // iterating over all MSECs
+                    for (auto smec_it : MSEC) {
+                        ValueType bestExit = 0;
+                        auto stateSet = smec_it.getStateSet();
+                        for (uint state : stateSet) {
+                            if (_psiStates[state]) {
+                                bestExit = 1;
+                                break;
+                            }
+                            if (_minimizerStates[state]) continue;
+                            uint rowGroupIndex = rowGroupIndices[state];
+                            auto exitingCompare = [&state, &smec_it, &choice_begin](const ValueType &lhs, const ValueType &rhs)
+                            {
+                                bool lhsExiting = !smec_it.containsChoice(state, (&lhs - &(*choice_begin)));
+                                bool rhsExiting = !smec_it.containsChoice(state, (&rhs - &(*choice_begin)));
+                                if( lhsExiting && !rhsExiting) return false;
+                                if(!lhsExiting &&  rhsExiting) return true;
+                                if(!lhsExiting && !rhsExiting) return false;
+                                return lhs < rhs;
+                            };
+                            uint rowGroupSize = rowGroupIndices[state + 1] - rowGroupIndex;
+
+                            auto choice_it = choice_begin + rowGroupIndex;
+                            auto it = std::max_element(choice_it, choice_it + rowGroupSize, exitingCompare);
+                            ValueType newBestExit = 0;
+                            if (!smec_it.containsChoice(state, it - choice_begin)) {
+                                newBestExit = *it;
+                            }
+                            if (newBestExit > bestExit)
+                                bestExit = newBestExit;
+                        }
+                        // deflating the states of the current MSEC
+                        for (uint state : stateSet) {
+                            xU[state] = std::min(xU[state], bestExit);
+                        }
+                    }
+                }
+
+                template <typename ValueType>
+                void SoundGameViHelper<ValueType>::reduceChoiceValues(std::vector<ValueType>& choiceValues, storm::storage::BitVector* result, std::vector<ValueType>& x)
+                {
+                    // result BitVec should be initialized with 1s outside the method
+
+                    auto rowGroupIndices = this->_transitionMatrix.getRowGroupIndices();
+                    auto choice_it = choiceValues.begin();
+
+                    for(uint state = 0; state < rowGroupIndices.size() - 1; state++) {
+                        uint rowGroupSize = rowGroupIndices[state + 1] - rowGroupIndices[state];
+                        ValueType optChoice;
+                        if (_minimizerStates[state]) {  // check if current state is minimizer state
+                            // getting the optimal minimizer choice for the given state
+                            optChoice = *std::min_element(choice_it, choice_it + rowGroupSize);
+
+                            if (result != nullptr) {
+                                for (uint choice = 0; choice < rowGroupSize; choice++, choice_it++) {
+                                    if (*choice_it > optChoice) {
+                                        result->set(rowGroupIndices[state] + choice, 0);
+                                    }
+                                }
+                            }
+                            else {
+                                choice_it += rowGroupSize;
+                            }
+                            // reducing the xNew() vector for minimizer states
+                            x[state] = optChoice;
+                        }
+                        else
+                        {
+                            optChoice = *std::max_element(choice_it, choice_it + rowGroupSize);
+                            // reducing the xNew() vector for maximizer states
+                            x[state] = optChoice;
+                            choice_it += rowGroupSize;
+                        }
+                    }
+                }
+
+
+                template <typename ValueType>
+                bool SoundGameViHelper<ValueType>::checkConvergence(ValueType threshold) const {
+                    STORM_LOG_ASSERT(_multiplier, "tried to check for convergence without doing an iteration first.");
+                    // Now check whether the currently produced results are precise enough
+                    STORM_LOG_ASSERT(threshold > storm::utility::zero<ValueType>(), "Did not expect a non-positive threshold.");
+                    auto x1It = xNewL().begin();
+                    auto x1Ite = xNewL().end();
+                    auto x2It = xNewU().begin();
+                    for (; x1It != x1Ite; x1It++, x2It++) {
+                        ValueType diff = (*x2It - *x1It);
+                        if (diff > threshold) {
+                            return false;
+                        }
+                    }
+                    return true;
+                }
+
+                template <typename ValueType>
+                void SoundGameViHelper<ValueType>::setProduceScheduler(bool value) {
+                    _produceScheduler = value;
+                }
+
+
+                template <typename ValueType>
+                bool SoundGameViHelper<ValueType>::isProduceSchedulerSet() const {
+                    return _produceScheduler;
+                }
+
+                template <typename ValueType>
+                void SoundGameViHelper<ValueType>::setShieldingTask(bool value) {
+                    _shieldingTask = value;
+                }
+
+                template <typename ValueType>
+                bool SoundGameViHelper<ValueType>::isShieldingTask() const {
+                    return _shieldingTask;
+                }
+
+                template <typename ValueType>
+                void SoundGameViHelper<ValueType>::updateTransitionMatrix(storm::storage::SparseMatrix<ValueType> newTransitionMatrix) {
+                    _transitionMatrix = newTransitionMatrix;
+                }
+
+                template <typename ValueType>
+                void SoundGameViHelper<ValueType>::updateStatesOfCoalition(storm::storage::BitVector newStatesOfCoalition) {
+                    _statesOfCoalition = newStatesOfCoalition;
+                }
+
+                template <typename ValueType>
+                std::vector<uint64_t> const& SoundGameViHelper<ValueType>::getProducedOptimalChoices() const {
+                    STORM_LOG_ASSERT(this->isProduceSchedulerSet(), "Trying to get the produced optimal choices although no scheduler was requested.");
+                    STORM_LOG_ASSERT(this->_producedOptimalChoices.is_initialized(), "Trying to get the produced optimal choices but none were available. Was there a computation call before?");
+                    return this->_producedOptimalChoices.get();
+                }
+
+                template <typename ValueType>
+                std::vector<uint64_t>& SoundGameViHelper<ValueType>::getProducedOptimalChoices() {
+                    STORM_LOG_ASSERT(this->isProduceSchedulerSet(), "Trying to get the produced optimal choices although no scheduler was requested.");
+                    STORM_LOG_ASSERT(this->_producedOptimalChoices.is_initialized(), "Trying to get the produced optimal choices but none were available. Was there a computation call before?");
+                    return this->_producedOptimalChoices.get();
+                }
+
+                template <typename ValueType>
+                storm::storage::Scheduler<ValueType> SoundGameViHelper<ValueType>::extractScheduler() const{
+                    auto const& optimalChoices = getProducedOptimalChoices();
+                    storm::storage::Scheduler<ValueType> scheduler(optimalChoices.size());
+                    for (uint64_t state = 0; state < optimalChoices.size(); ++state) {
+                        scheduler.setChoice(optimalChoices[state], state);
+                    }
+                    return scheduler;
+                }
+
+                template <typename ValueType>
+                void SoundGameViHelper<ValueType>::getChoiceValues(Environment const& env, std::vector<ValueType> const& x, std::vector<ValueType>& choiceValues) {
+                    _multiplier->multiply(env, x, nullptr, choiceValues);
+                }
+
+                template <typename ValueType>
+                void SoundGameViHelper<ValueType>::fillChoiceValuesVector(std::vector<ValueType>& choiceValues, storm::storage::BitVector psiStates, std::vector<storm::storage::SparseMatrix<double>::index_type> rowGroupIndices) {
+                    std::vector<ValueType> allChoices = std::vector<ValueType>(rowGroupIndices.at(rowGroupIndices.size() - 1), storm::utility::zero<ValueType>());
+                    auto choice_it = choiceValues.begin();
+                    for(uint state = 0; state < rowGroupIndices.size() - 1; state++) {
+                        uint rowGroupSize = rowGroupIndices[state + 1] - rowGroupIndices[state];
+                        if (psiStates.get(state)) {
+                            for(uint choice = 0; choice < rowGroupSize; choice++, choice_it++) {
+                                allChoices.at(rowGroupIndices.at(state) + choice) = *choice_it;
+                            }
+                        }
+                    }
+                    choiceValues = allChoices;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType>& SoundGameViHelper<ValueType>::xNewL() {
+                    return _x1IsCurrent ? _x1L : _x2L;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType> const& SoundGameViHelper<ValueType>::xNewL() const {
+                    return _x1IsCurrent ? _x1L : _x2L;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType>& SoundGameViHelper<ValueType>::xOldL() {
+                    return _x1IsCurrent ? _x2L : _x1L;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType> const& SoundGameViHelper<ValueType>::xOldL() const {
+                    return _x1IsCurrent ? _x2L : _x1L;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType>& SoundGameViHelper<ValueType>::xNewU() {
+                    return _x1IsCurrent ? _x1U : _x2U;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType> const& SoundGameViHelper<ValueType>::xNewU() const {
+                    return _x1IsCurrent ? _x1U : _x2U;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType>& SoundGameViHelper<ValueType>::xOldU() {
+                    return _x1IsCurrent ? _x2U : _x1U;
+                }
+
+                template <typename ValueType>
+                std::vector<ValueType> const& SoundGameViHelper<ValueType>::xOldU() const {
+                    return _x1IsCurrent ? _x2U : _x1U;
+                }
+
+                template class SoundGameViHelper<double>;
+#ifdef STORM_HAVE_CARL
+                template class SoundGameViHelper<storm::RationalNumber>;
+#endif
+            }
+        }
+    }
+}
diff --git a/src/storm/modelchecker/rpatl/helper/internal/SoundGameViHelper.h b/src/storm/modelchecker/rpatl/helper/internal/SoundGameViHelper.h
new file mode 100644
index 000000000..e90099fde
--- /dev/null
+++ b/src/storm/modelchecker/rpatl/helper/internal/SoundGameViHelper.h
@@ -0,0 +1,136 @@
+#pragma once
+
+#include "storm/storage/SparseMatrix.h"
+#include "storm/solver/LinearEquationSolver.h"
+#include "storm/solver/MinMaxLinearEquationSolver.h"
+#include "storm/solver/Multiplier.h"
+#include "storm/storage/MaximalEndComponentDecomposition.h"
+
+namespace storm {
+    class Environment;
+
+    namespace storage {
+        template <typename VT> class Scheduler;
+    }
+
+    namespace modelchecker {
+        namespace helper {
+            namespace internal {
+
+                template <typename ValueType>
+                class SoundGameViHelper {
+                public:
+                    SoundGameViHelper(storm::storage::SparseMatrix<ValueType> const& transitionMatrix, storm::storage::SparseMatrix<ValueType> const& backwardTransitions, std::vector<ValueType> b, storm::storage::BitVector statesOfCoalition, storm::storage::BitVector psiStates, OptimizationDirection const& optimizationDirection);
+
+                    void prepareSolversAndMultipliers(const Environment& env);
+
+                    /*!
+                     * Perform value iteration until convergence
+                     */
+                    void performValueIteration(Environment const& env, std::vector<ValueType>& xL, std::vector<ValueType>& xU, storm::solver::OptimizationDirection const dir, std::vector<ValueType>& constrainedChoiceValues);
+
+                    /*!
+                     * Sets whether an optimal scheduler shall be constructed during the computation
+                     */
+                    void setProduceScheduler(bool value);
+
+                    /*!
+                     * @return whether an optimal scheduler shall be constructed during the computation
+                     */
+                    bool isProduceSchedulerSet() const;
+
+                    /*!
+                     * Sets whether an optimal scheduler shall be constructed during the computation
+                     */
+                    void setShieldingTask(bool value);
+
+                    /*!
+                     * @return whether an optimal scheduler shall be constructed during the computation
+                     */
+                    bool isShieldingTask() const;
+
+                    /*!
+                     * Changes the transitionMatrix to the given one.
+                     */
+                    void updateTransitionMatrix(storm::storage::SparseMatrix<ValueType> newTransitionMatrix);
+
+                    /*!
+                     * Changes the statesOfCoalition to the given one.
+                     */
+                    void updateStatesOfCoalition(storm::storage::BitVector newStatesOfCoalition);
+
+                    storm::storage::Scheduler<ValueType> extractScheduler() const;
+
+                    void getChoiceValues(Environment const& env, std::vector<ValueType> const& x, std::vector<ValueType>& choiceValues);
+
+                    /*!
+                     * Fills the choice values vector to the original size with zeros for ~psiState choices.
+                     */
+                    void fillChoiceValuesVector(std::vector<ValueType>& choiceValues, storm::storage::BitVector psiStates, std::vector<storm::storage::SparseMatrix<double>::index_type> rowGroupIndices);
+
+                    void deflate(storm::storage::MaximalEndComponentDecomposition<ValueType> const MECD, storage::SparseMatrix<ValueType> const restrictedMatrix, std::vector<ValueType>& xU, std::vector<ValueType> choiceValues);
+
+                    void reduceChoiceValues(std::vector<ValueType>& choiceValues, storm::storage::BitVector* result, std::vector<ValueType>& x);
+
+                private:
+                    /*!
+                     * Performs one iteration step for value iteration
+                     */
+                    void performIterationStep(Environment const& env, storm::solver::OptimizationDirection const dir, std::vector<uint64_t>* choices = nullptr);
+
+                    /*!
+                     * Checks whether the curently computed value achieves the desired precision
+                     */
+                    bool checkConvergence(ValueType precision) const;
+
+                    std::vector<ValueType>& xNewL();
+                    std::vector<ValueType> const& xNewL() const;
+
+                    std::vector<ValueType>& xOldL();
+                    std::vector<ValueType> const& xOldL() const;
+
+                    std::vector<ValueType>& xNewU();
+                    std::vector<ValueType> const& xNewU() const;
+
+                    std::vector<ValueType>& xOldU();
+                    std::vector<ValueType> const& xOldU() const;
+
+                    bool _x1IsCurrent;
+
+                    storm::storage::BitVector _minimizerStates;
+
+                    /*!
+                     * @pre before calling this, a computation call should have been performed during which scheduler production was enabled.
+                     * @return the produced scheduler of the most recent call.
+                     */
+                    std::vector<uint64_t> const& getProducedOptimalChoices() const;
+
+                    /*!
+                     * @pre before calling this, a computation call should have been performed during which scheduler production was enabled.
+                     * @return the produced scheduler of the most recent call.
+                     */
+                    std::vector<uint64_t>& getProducedOptimalChoices();
+
+                    std::unique_ptr<storm::solver::Multiplier<ValueType>> _multiplier;
+
+                    storm::storage::SparseMatrix<ValueType> _transitionMatrix;
+                    storm::storage::SparseMatrix<ValueType> _backwardTransitions;
+                    storm::storage::SparseMatrix<ValueType> _restrictedTransitions;
+                    storm::storage::BitVector _oldPolicy;
+                    storm::storage::BitVector _statesOfCoalition;
+                    storm::storage::BitVector _psiStates;
+                    std::vector<ValueType> _x, _x1L, _x2L, _x1U, _x2U, _b;
+                    OptimizationDirection _optimizationDirection;
+
+                    storm::storage::MaximalEndComponentDecomposition<ValueType> _MSECs;
+
+                    bool _produceScheduler = false;
+                    bool _shieldingTask = false;
+                    boost::optional<std::vector<uint64_t>> _producedOptimalChoices;
+
+                    std::vector<double> _timing;
+                };
+            }
+        }
+    }
+}
diff --git a/src/storm/storage/MaximalEndComponent.cpp b/src/storm/storage/MaximalEndComponent.cpp
index aa7453277..d4f51e089 100644
--- a/src/storm/storage/MaximalEndComponent.cpp
+++ b/src/storm/storage/MaximalEndComponent.cpp
@@ -4,7 +4,6 @@
 
 namespace storm {
     namespace storage {
-
         std::ostream& operator<<(std::ostream& out, storm::storage::FlatSet<uint_fast64_t> const& block);
 
         MaximalEndComponent::MaximalEndComponent() : stateToChoicesMapping() {
@@ -100,6 +99,18 @@ namespace storm {
             return stateChoicePair->second.find(choice) != stateChoicePair->second.end();
         }
 
+        template<typename ValueType>
+        bool MaximalEndComponent::isErgodic(storm::storage::SparseMatrix<ValueType> transitionMatrix) const {
+            auto rowGroupIndices = transitionMatrix.getRowGroupIndices();
+            for (auto state : this->getStateSet())
+            {
+                if (getChoicesForState(state).size() == (rowGroupIndices[state + 1] - rowGroupIndices[state])) continue;
+                return false;
+            }
+            return true;
+        }
+
+
         MaximalEndComponent::set_type MaximalEndComponent::getStateSet() const {
             set_type states;
             states.reserve(stateToChoicesMapping.size());
@@ -136,5 +147,8 @@ namespace storm {
         MaximalEndComponent::const_iterator MaximalEndComponent::end() const {
             return stateToChoicesMapping.end();
         }
+
+        template bool MaximalEndComponent::isErgodic<double>(storm::storage::SparseMatrix<double> transitionMatrix) const;
+        template bool MaximalEndComponent::isErgodic<storm::RationalNumber>(storm::storage::SparseMatrix<storm::RationalNumber> transitionMatrix) const;
     }
 }
diff --git a/src/storm/storage/MaximalEndComponent.h b/src/storm/storage/MaximalEndComponent.h
index a1d5b37c2..448159804 100644
--- a/src/storm/storage/MaximalEndComponent.h
+++ b/src/storm/storage/MaximalEndComponent.h
@@ -5,6 +5,7 @@
 
 #include "storm/storage/sparse/StateType.h"
 #include "storm/storage/BoostTypes.h"
+#include "storm/storage/SparseMatrix.h"
 
 namespace storm {
     namespace storage {
@@ -20,6 +21,7 @@ namespace storm {
             typedef std::unordered_map<uint_fast64_t, set_type> map_type;
             typedef map_type::iterator iterator;
             typedef map_type::const_iterator const_iterator;
+
             
             /*!
              * Creates an empty MEC.
@@ -124,6 +126,15 @@ namespace storm {
              * @return True if the given choice is contained in the MEC.
              */
             bool containsChoice(uint_fast64_t state, uint_fast64_t choice) const;
+
+            /*!
+             * Retrieves whether the MEC is ergodic or not i.e. wether the MEC is exitable or not
+             *
+             * @param transitionMatrix the given transition matrix
+             * @return True if the MEC is ergodic
+             */
+            template<typename ValueType>
+            bool isErgodic(storm::storage::SparseMatrix<ValueType> transitionMatrix) const;
             
             /*!
              * Retrieves the set of states contained in the MEC.
diff --git a/src/test/storm/modelchecker/rpatl/smg/SmgRpatlModelCheckerTest.cpp b/src/test/storm/modelchecker/rpatl/smg/SmgRpatlModelCheckerTest.cpp
index 79217c614..765d08135 100644
--- a/src/test/storm/modelchecker/rpatl/smg/SmgRpatlModelCheckerTest.cpp
+++ b/src/test/storm/modelchecker/rpatl/smg/SmgRpatlModelCheckerTest.cpp
@@ -17,6 +17,11 @@
 #include "storm/settings/modules/CoreSettings.h"
 #include "storm/logic/Formulas.h"
 #include "storm/exceptions/UncheckedRequirementException.h"
+#include "storm/solver/Multiplier.h"
+#include "storm/storage/SparseMatrix.h"
+#include "storm/utility/graph.h"
+#include "storm/storage/MaximalEndComponentDecomposition.h"
+#include "storm/modelchecker/rpatl/helper/internal/SoundGameViHelper.h"
 
 namespace {
 
@@ -345,5 +350,286 @@ namespace {
         EXPECT_NEAR(this->parseNumber("1"), this->getQuantitativeResultAtInitialState(model, result), this->precision());
     }
 
+    TYPED_TEST(SmgRpatlModelCheckerTest, Deflate) {
+        typedef double ValueType;
+        std::string formulasString = " <<maxP>> Pmax=? [F (s=2)]";
+
+        auto modelFormulas = this->buildModelFormulas(STORM_TEST_RESOURCES_DIR "/smg/example_smg.nm", formulasString);
+        auto model = std::move(modelFormulas.first);
+        auto tasks = this->getTasks(modelFormulas.second);
+        auto checker = this->createModelChecker(model);
+        std::unique_ptr<storm::modelchecker::CheckResult> result;
+        auto transitionMatrix = model->getTransitionMatrix();
+
+        auto formulas = std::move(modelFormulas.second);
+        storm::logic::GameFormula const& gameFormula = formulas[0]->asGameFormula();
+
+        storm::modelchecker::CheckTask<storm::logic::GameFormula, ValueType> checkTask(gameFormula);
+
+        storm::storage::BitVector statesOfCoalition = model->computeStatesOfCoalition(gameFormula.getCoalition());
+        statesOfCoalition.complement();
+
+
+        storm::storage::BitVector psiStates = checker->check(this->env(), gameFormula.getSubformula().asProbabilityOperatorFormula().getSubformula().asEventuallyFormula().getSubformula().asStateFormula())->asExplicitQualitativeCheckResult().getTruthValuesVector();
+        storm::storage::BitVector phiStates(model->getNumberOfStates(), true);
+
+        storm::storage::SparseMatrix<ValueType> backwardTransitions = model->getBackwardTransitions();
+        storm::OptimizationDirection optimizationDirection = gameFormula.getSubformula().asOperatorFormula().getOptimalityType();
+        auto minimizerStates = optimizationDirection == storm::OptimizationDirection::Maximize ? statesOfCoalition : ~statesOfCoalition;
+
+        storm::modelchecker::helper::internal::SoundGameViHelper<ValueType> viHelper(transitionMatrix, backwardTransitions, statesOfCoalition, psiStates, optimizationDirection);
+        viHelper.prepareSolversAndMultipliers(this->env());
+
+        std::vector<ValueType> xL = std::vector<ValueType>(transitionMatrix.getRowGroupCount(), storm::utility::zero<ValueType>());
+        for (size_t i = 0; i < xL.size(); i++)
+        {
+            if (psiStates[i])
+                xL[i] = 1;
+        }
+
+        std::vector<ValueType> xU = std::vector<ValueType>(transitionMatrix.getRowGroupCount(), storm::utility::zero<ValueType>());
+        storm::storage::BitVector probGreater0 = storm::utility::graph::performProbGreater0(backwardTransitions, phiStates, psiStates);
+        auto xU_begin = xU.begin();
+        std::for_each(xU.begin(), xU.end(), [&probGreater0, &xU_begin](ValueType &it)
+                      {
+                          if (probGreater0[&it - &(*xU_begin)])
+                              it = 1;
+                      });
+
+        // performValueIteration
+        std::vector<ValueType> _x1L = xL;
+        std::vector<ValueType> _x2L = _x1L;
+
+        std::vector<ValueType> _x1U = xU;
+        std::vector<ValueType> _x2U = _x1U;
+
+        // perform first iteration step
+        storm::storage::BitVector reducedMinimizerActions = {storm::storage::BitVector(transitionMatrix.getRowCount(), true)};
+        std::vector<ValueType> choiceValuesL = std::vector<ValueType>(transitionMatrix.getRowCount(), storm::utility::zero<ValueType>());
+
+        viHelper._multiplier->multiply(this->env(), _x2L, nullptr, choiceValuesL);
+        viHelper.reduceChoiceValues(choiceValuesL, &reducedMinimizerActions, _x1L);
+
+
+        // over approximation
+        std::vector<ValueType> choiceValuesU = std::vector<ValueType>(transitionMatrix.getRowCount(), storm::utility::zero<ValueType>());
+
+        viHelper._multiplier->multiply(this->env(), _x2U, nullptr, choiceValuesU);
+        viHelper.reduceChoiceValues(choiceValuesU, nullptr, _x1U);
+
+        storm::storage::SparseMatrix<ValueType> restrictedTransMatrix = transitionMatrix.restrictRows(reducedMinimizerActions);
+
+        storm::storage::MaximalEndComponentDecomposition<ValueType> MSEC = storm::storage::MaximalEndComponentDecomposition<ValueType>(restrictedTransMatrix, backwardTransitions);
+
+        // testing MSEC
+        // =====================================================
+        ASSERT_TRUE(MSEC.size() == 3);
+        storm::storage::MaximalEndComponent const& mec1 = MSEC[0];
+        if (mec1.containsState(0)) {
+            ASSERT_TRUE(mec1.containsState(1));
+            ASSERT_FALSE(mec1.containsState(2));
+            ASSERT_FALSE(mec1.containsState(3));
+        }
+        else if (mec1.containsState(2)) {
+            ASSERT_FALSE(mec1.containsState(0));
+            ASSERT_FALSE(mec1.containsState(1));
+            ASSERT_FALSE(mec1.containsState(3));
+        }
+        else if (mec1.containsState(3)) {
+            ASSERT_FALSE(mec1.containsState(0));
+            ASSERT_FALSE(mec1.containsState(1));
+            ASSERT_FALSE(mec1.containsState(2));
+        }
+        else {
+            // This case must never happen
+            ASSERT_TRUE(false);
+        }
+
+        storm::storage::MaximalEndComponent const& mec2 = MSEC[1];
+        if (mec2.containsState(0)) {
+            ASSERT_TRUE(mec2.containsState(1));
+            ASSERT_FALSE(mec2.containsState(2));
+            ASSERT_FALSE(mec2.containsState(3));
+        }
+        else if (mec2.containsState(2)) {
+            ASSERT_FALSE(mec2.containsState(0));
+            ASSERT_FALSE(mec2.containsState(1));
+            ASSERT_FALSE(mec2.containsState(3));
+        }
+        else if (mec2.containsState(3)) {
+            ASSERT_FALSE(mec2.containsState(0));
+            ASSERT_FALSE(mec2.containsState(1));
+            ASSERT_FALSE(mec2.containsState(2));
+        }
+        else {
+            // This case must never happen
+            ASSERT_TRUE(false);
+        }
+
+        storm::storage::MaximalEndComponent const& mec3 = MSEC[2];
+        if (mec3.containsState(0)) {
+            ASSERT_TRUE(mec3.containsState(1));
+            ASSERT_FALSE(mec3.containsState(2));
+            ASSERT_FALSE(mec3.containsState(3));
+        }
+        else if (mec3.containsState(2)) {
+            ASSERT_FALSE(mec3.containsState(0));
+            ASSERT_FALSE(mec3.containsState(1));
+            ASSERT_FALSE(mec3.containsState(3));
+        }
+        else if (mec3.containsState(3)) {
+            ASSERT_FALSE(mec3.containsState(0));
+            ASSERT_FALSE(mec3.containsState(1));
+            ASSERT_FALSE(mec3.containsState(2));
+        }
+        else {
+            // This case must never happen
+            ASSERT_TRUE(false);
+        }
+        // =====================================================
+
+        // reducing the choiceValuesU
+        size_t i = 0;
+        auto new_end = std::remove_if(choiceValuesU.begin(), choiceValuesU.end(), [&reducedMinimizerActions, &i](const auto& item) {
+            bool ret = !(reducedMinimizerActions[i]);
+            i++;
+            return ret;
+        });
+        choiceValuesU.erase(new_end, choiceValuesU.end());
+
+        // deflating the MSECs
+        viHelper.deflate(MSEC, restrictedTransMatrix, _x1U, choiceValuesU);
+
+        xL = _x1L;
+        xU = _x1U;
+
+        // testing x vectors
+        // =====================================================
+        EXPECT_NEAR(this->parseNumber("0"), xL[0], this->precision());
+        EXPECT_NEAR(this->parseNumber("0.333333"), xL[1], this->precision());
+        EXPECT_NEAR(this->parseNumber("1"), xL[2], this->precision());
+        EXPECT_NEAR(this->parseNumber("0"), xL[3], this->precision());
+
+        EXPECT_NEAR(this->parseNumber("0.666666"), xU[0], this->precision());
+        EXPECT_NEAR(this->parseNumber("0.666666"), xU[1], this->precision());
+        EXPECT_NEAR(this->parseNumber("1"), xU[2], this->precision());
+        EXPECT_NEAR(this->parseNumber("0"), xU[3], this->precision());
+        // =====================================================
+
+        // perform second iteration step
+        reducedMinimizerActions = {storm::storage::BitVector(transitionMatrix.getRowCount(), true)};
+        choiceValuesL = std::vector<ValueType>(transitionMatrix.getRowCount(), storm::utility::zero<ValueType>());
+
+        viHelper._multiplier->multiply(this->env(), _x1L, nullptr, choiceValuesL);
+        viHelper.reduceChoiceValues(choiceValuesL, &reducedMinimizerActions, _x2L);
+
+
+        // over approximation
+        choiceValuesU = std::vector<ValueType>(transitionMatrix.getRowCount(), storm::utility::zero<ValueType>());
+
+        viHelper._multiplier->multiply(this->env(), _x1U, nullptr, choiceValuesU);
+        viHelper.reduceChoiceValues(choiceValuesU, nullptr, _x2U);
+
+        restrictedTransMatrix = transitionMatrix.restrictRows(reducedMinimizerActions);
+
+        MSEC = storm::storage::MaximalEndComponentDecomposition<ValueType>(restrictedTransMatrix, backwardTransitions);
+
+        // testing MSEC
+        // =====================================================
+        ASSERT_TRUE(MSEC.size() == 3);
+        storm::storage::MaximalEndComponent const& mec4 = MSEC[0];
+        if (mec4.containsState(0)) {
+            ASSERT_TRUE(mec4.containsState(1));
+            ASSERT_FALSE(mec4.containsState(2));
+            ASSERT_FALSE(mec4.containsState(3));
+        }
+        else if (mec4.containsState(2)) {
+            ASSERT_FALSE(mec4.containsState(0));
+            ASSERT_FALSE(mec4.containsState(1));
+            ASSERT_FALSE(mec4.containsState(3));
+        }
+        else if (mec4.containsState(3)) {
+            ASSERT_FALSE(mec4.containsState(0));
+            ASSERT_FALSE(mec4.containsState(1));
+            ASSERT_FALSE(mec4.containsState(2));
+        }
+        else {
+            // This case must never happen
+            ASSERT_TRUE(false);
+        }
+
+        storm::storage::MaximalEndComponent const& mec5 = MSEC[1];
+        if (mec5.containsState(0)) {
+            ASSERT_TRUE(mec5.containsState(1));
+            ASSERT_FALSE(mec5.containsState(2));
+            ASSERT_FALSE(mec5.containsState(3));
+        }
+        else if (mec5.containsState(2)) {
+            ASSERT_FALSE(mec5.containsState(0));
+            ASSERT_FALSE(mec5.containsState(1));
+            ASSERT_FALSE(mec5.containsState(3));
+        }
+        else if (mec5.containsState(3)) {
+            ASSERT_FALSE(mec5.containsState(0));
+            ASSERT_FALSE(mec5.containsState(1));
+            ASSERT_FALSE(mec5.containsState(2));
+        }
+        else {
+            // This case must never happen
+            ASSERT_TRUE(false);
+        }
+
+        storm::storage::MaximalEndComponent const& mec6 = MSEC[2];
+        if (mec6.containsState(0)) {
+            ASSERT_TRUE(mec6.containsState(1));
+            ASSERT_FALSE(mec6.containsState(2));
+            ASSERT_FALSE(mec6.containsState(3));
+        }
+        else if (mec6.containsState(2)) {
+            ASSERT_FALSE(mec6.containsState(0));
+            ASSERT_FALSE(mec6.containsState(1));
+            ASSERT_FALSE(mec6.containsState(3));
+        }
+        else if (mec6.containsState(3)) {
+            ASSERT_FALSE(mec6.containsState(0));
+            ASSERT_FALSE(mec6.containsState(1));
+            ASSERT_FALSE(mec6.containsState(2));
+        }
+        else {
+            // This case must never happen
+            ASSERT_TRUE(false);
+        }
+        // =====================================================
+
+        // reducing the choiceValuesU
+        i = 0;
+        new_end = std::remove_if(choiceValuesU.begin(), choiceValuesU.end(), [&reducedMinimizerActions, &i](const auto& item) {
+            bool ret = !(reducedMinimizerActions[i]);
+            i++;
+            return ret;
+        });
+        choiceValuesU.erase(new_end, choiceValuesU.end());
+
+        // deflating the MSECs
+        viHelper.deflate(MSEC, restrictedTransMatrix, _x2U, choiceValuesU);
+
+        xL = _x2L;
+        xU = _x2U;
+
+        // testing x vectors
+        // =====================================================
+        EXPECT_NEAR(this->parseNumber("0.333333"), xL[0], this->precision());
+        EXPECT_NEAR(this->parseNumber("0.444444"), xL[1], this->precision());
+        EXPECT_NEAR(this->parseNumber("1"), xL[2], this->precision());
+        EXPECT_NEAR(this->parseNumber("0"), xL[3], this->precision());
+
+        EXPECT_NEAR(this->parseNumber("0.555555"), xU[0], this->precision());
+        EXPECT_NEAR(this->parseNumber("0.555555"), xU[1], this->precision());
+        EXPECT_NEAR(this->parseNumber("1"), xU[2], this->precision());
+        EXPECT_NEAR(this->parseNumber("0"), xU[3], this->precision());
+        // =====================================================
+
+    }
+
     // TODO: create more test cases (files)
 }