From aa6ed893df700767b7b191ffd787474945c00e80 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?M=C3=BCller=2C=20Felix?=
 <felix.mueller2@mailbox.tu-dresden.de>
Date: Fri, 14 Jun 2019 10:36:05 +0200
Subject: [PATCH] Changed ISTL solver interface to use parallel solver; Added
 empty communicator for sequential use of parallel solvers

---
 src/amdis/LinearAlgebra.hpp                   |   3 +
 src/amdis/ProblemStat.hpp                     |   8 +-
 src/amdis/ProblemStat.inc.hpp                 |   4 +-
 src/amdis/functions/GlobalIdSet.hpp           |  17 ++-
 src/amdis/linearalgebra/Common.hpp            |  28 ++++
 src/amdis/linearalgebra/LinearSolver.hpp      |  15 +-
 .../linearalgebra/LinearSolverInterface.hpp   |  14 +-
 .../linearalgebra/PreconditionerInterface.hpp |   6 +-
 src/amdis/linearalgebra/RunnerInterface.hpp   |  10 +-
 src/amdis/linearalgebra/eigen/CMakeLists.txt  |   1 +
 .../linearalgebra/eigen/DirectRunner.hpp      |  29 ++--
 .../linearalgebra/eigen/IterativeRunner.hpp   |  25 ++--
 .../linearalgebra/eigen/SolverCreator.hpp     |  45 +++---
 src/amdis/linearalgebra/eigen/Traits.hpp      |  15 ++
 src/amdis/linearalgebra/istl/CMakeLists.txt   |   4 +
 .../linearalgebra/istl/Communication.hpp      | 105 +++++++++++++
 .../linearalgebra/istl/Communication.inc.hpp  | 139 ++++++++++++++++++
 src/amdis/linearalgebra/istl/Creators.hpp     |  97 ++++++++++++
 src/amdis/linearalgebra/istl/DirectRunner.hpp |  28 ++--
 src/amdis/linearalgebra/istl/ISTLRunner.hpp   |  69 ++++++---
 .../istl/ISTL_Preconditioner.hpp              |  20 +--
 src/amdis/linearalgebra/istl/ISTL_Solver.hpp  |  97 ++++++------
 src/amdis/linearalgebra/istl/Traits.hpp       |  26 ++++
 src/amdis/linearalgebra/mtl/CMakeLists.txt    |   1 +
 .../linearalgebra/mtl/ITL_Preconditioner.hpp  |  29 ++--
 src/amdis/linearalgebra/mtl/ITL_Solver.hpp    |  18 +--
 src/amdis/linearalgebra/mtl/KrylovRunner.hpp  |  16 +-
 .../linearalgebra/mtl/Preconditioner.hpp      |   8 +-
 src/amdis/linearalgebra/mtl/Traits.hpp        |  15 ++
 src/amdis/linearalgebra/mtl/UmfpackRunner.hpp |  28 ++--
 test/CMakeLists.txt                           |   6 +
 test/ISTLCommTest.cpp                         |  92 ++++++++++++
 32 files changed, 822 insertions(+), 196 deletions(-)
 create mode 100644 src/amdis/linearalgebra/eigen/Traits.hpp
 create mode 100644 src/amdis/linearalgebra/istl/Communication.hpp
 create mode 100644 src/amdis/linearalgebra/istl/Communication.inc.hpp
 create mode 100644 src/amdis/linearalgebra/istl/Creators.hpp
 create mode 100644 src/amdis/linearalgebra/istl/Traits.hpp
 create mode 100644 src/amdis/linearalgebra/mtl/Traits.hpp
 create mode 100644 test/ISTLCommTest.cpp

diff --git a/src/amdis/LinearAlgebra.hpp b/src/amdis/LinearAlgebra.hpp
index 9a32bd9a..faae0063 100644
--- a/src/amdis/LinearAlgebra.hpp
+++ b/src/amdis/LinearAlgebra.hpp
@@ -10,6 +10,7 @@
 #include <amdis/linearalgebra/mtl/DOFVector.hpp>
 #include <amdis/linearalgebra/mtl/ITL_Solver.hpp>
 #include <amdis/linearalgebra/mtl/ITL_Preconditioner.hpp>
+#include <amdis/linearalgebra/mtl/Traits.hpp>
 
 #elif HAVE_EIGEN
 
@@ -17,6 +18,7 @@
 #include <amdis/linearalgebra/eigen/DOFMatrix.hpp>
 #include <amdis/linearalgebra/eigen/DOFVector.hpp>
 #include <amdis/linearalgebra/eigen/SolverCreator.hpp>
+#include <amdis/linearalgebra/eigen/Traits.hpp>
 
 #else // ISTL
 
@@ -25,5 +27,6 @@
 #include <amdis/linearalgebra/istl/DOFVector.hpp>
 #include <amdis/linearalgebra/istl/ISTL_Solver.hpp>
 #include <amdis/linearalgebra/istl/ISTL_Preconditioner.hpp>
+#include <amdis/linearalgebra/istl/Traits.hpp>
 
 #endif
\ No newline at end of file
diff --git a/src/amdis/ProblemStat.hpp b/src/amdis/ProblemStat.hpp
index 1029dcf8..54e0c8f3 100644
--- a/src/amdis/ProblemStat.hpp
+++ b/src/amdis/ProblemStat.hpp
@@ -11,7 +11,6 @@
 #include <dune/common/fvector.hh>
 #include <dune/common/fmatrix.hh>
 #include <dune/grid/common/grid.hh>
-
 #include <amdis/AdaptInfo.hpp>
 #include <amdis/CreatorInterface.hpp>
 #include <amdis/CreatorMap.hpp>
@@ -72,8 +71,13 @@ namespace AMDiS
 
     using SystemMatrix = DOFMatrix<GlobalBasis, GlobalBasis, typename Traits::CoefficientType>;
     using SystemVector = DOFVector<GlobalBasis, typename Traits::CoefficientType>;
+    using LinearSolverTraits = SolverTraits<typename SystemMatrix::BaseMatrix,
+                                            typename SystemVector::BaseVector,
+                                            typename SystemVector::BaseVector,
+                                            GlobalBasis>;
 
-    using LinearSolverType = LinearSolverInterface<typename SystemMatrix::BaseMatrix, typename SystemVector::BaseVector>;
+    using LinearSolverType = LinearSolverInterface<LinearSolverTraits>;
+    using CommInfo = typename LinearSolverTraits::Comm;
 
   public:
     /**
diff --git a/src/amdis/ProblemStat.inc.hpp b/src/amdis/ProblemStat.inc.hpp
index 34d552a6..dda726e4 100644
--- a/src/amdis/ProblemStat.inc.hpp
+++ b/src/amdis/ProblemStat.inc.hpp
@@ -309,10 +309,10 @@ solve(AdaptInfo& adaptInfo, bool createMatrixData, bool storeMatrixData)
   solverInfo.setCreateMatrixData(createMatrixData);
   solverInfo.setStoreMatrixData(storeMatrixData);
 
-  solution_->compress();
+  auto commInfo = CommInfo::create(*globalBasis_, name_ + "->solver");
 
   linearSolver_->solve(systemMatrix_->matrix(), solution_->vector(), rhs_->vector(),
-                      solverInfo);
+                      *commInfo, solverInfo);
 
   if (solverInfo.info() > 0) {
     msg("solution of discrete system needed {} seconds", t.elapsed());
diff --git a/src/amdis/functions/GlobalIdSet.hpp b/src/amdis/functions/GlobalIdSet.hpp
index b2c089d0..ee0674c2 100644
--- a/src/amdis/functions/GlobalIdSet.hpp
+++ b/src/amdis/functions/GlobalIdSet.hpp
@@ -81,10 +81,23 @@ namespace AMDiS
     using GridView = typename GlobalBasis::GridView;
     using Grid = typename GridView::Grid;
     using Element = typename GridView::template Codim<0>::Entity;
-    using EntityIdType = typename Grid::GlobalIdSet::IdType; 
-    using IdType = std::pair<EntityIdType, std::size_t>;
+    using EntityIdType = typename Grid::GlobalIdSet::IdType;
     using PartitionType = Dune::PartitionType;
 
+    struct IdType : std::pair<EntityIdType, std::size_t>
+    {
+      using Super = std::pair<EntityIdType, std::size_t>;
+
+      IdType(int i = 0) : Super() {};
+      using Super::Super;
+
+      friend std::ostream& operator<<(std::ostream& os, IdType const& id)
+      {
+        os << "(" << id.first << "," << id.second << ")";
+        return os;
+      }
+    };
+
     using PreBasis = typename GlobalBasis::PreBasis;
     using TreePath = typename GlobalBasis::PrefixPath;
     using NodeIdSet = AMDiS::NodeIdSet<PreBasis, TreePath>;
diff --git a/src/amdis/linearalgebra/Common.hpp b/src/amdis/linearalgebra/Common.hpp
index 197cfe99..c4fa48e3 100644
--- a/src/amdis/linearalgebra/Common.hpp
+++ b/src/amdis/linearalgebra/Common.hpp
@@ -1,6 +1,8 @@
 #pragma once
 
 #include <cstddef>
+#include <memory>
+#include <string>
 
 namespace AMDiS
 {
@@ -11,4 +13,30 @@ namespace AMDiS
     T value;
   };
 
+  template <class Basis>
+  class DefaultCommunication
+  {
+  public:
+    static std::unique_ptr<DefaultCommunication> create(Basis const& basis, std::string const& prefix)
+    {
+      DUNE_UNUSED_PARAMETER(basis);
+      DUNE_UNUSED_PARAMETER(prefix);
+      return std::make_unique<DefaultCommunication>();
+    }
+  };
+
+  /** Base traits class for a linear solver for the system AX=B using an FE space described by a
+   *  dune-functions Basis. This defines the general interface typedefs, all implementations are
+   *  required to provide the typedefs listed here, by e.g. inheriting from this.
+   */
+  template <class A, class X, class B, class Basis>
+  class SolverTraitsBase
+  {
+  public:
+    using Mat = A;
+    using Sol = X;
+    using Rhs = B;
+    using Comm = DefaultCommunication<Basis>;
+  };
+
 } // end namespace AMDiS
diff --git a/src/amdis/linearalgebra/LinearSolver.hpp b/src/amdis/linearalgebra/LinearSolver.hpp
index fc62ce2f..fda3ff36 100644
--- a/src/amdis/linearalgebra/LinearSolver.hpp
+++ b/src/amdis/linearalgebra/LinearSolver.hpp
@@ -20,13 +20,18 @@ namespace AMDiS
    * solvers where the backend provides an interface, can be assigned
    * by different Runner objects.
    **/
-  template <class Mat, class Sol, class Rhs, class Runner>
+  template <class Traits, class Runner>
   class LinearSolver
-      : public LinearSolverInterface<Mat, Sol, Rhs>
+      : public LinearSolverInterface<Traits>
   {
     using Self = LinearSolver;
-    using Super = LinearSolverInterface<Mat, Sol, Rhs>;
+    using Super = LinearSolverInterface<Traits>;
+
     using RunnerBase = typename Super::RunnerBase;
+    using Mat = typename Traits::Mat;
+    using Sol = typename Traits::Sol;
+    using Rhs = typename Traits::Rhs;
+    using Comm = typename Traits::Comm;
 
   public:
     /// A creator to be used instead of the constructor.
@@ -52,12 +57,12 @@ namespace AMDiS
 
   private:
     /// Implements \ref LinearSolverInterface::solveSystemImpl()
-    void solveImpl(Mat const& A, Sol& x, Rhs const& b, SolverInfo& solverInfo) override
+    void solveImpl(Mat const& A, Sol& x, Rhs const& b, Comm& comm, SolverInfo& solverInfo) override
     {
       Dune::Timer t;
       if (solverInfo.doCreateMatrixData()) {
         // init matrix or wrap block-matrix or ...
-        runner_->init(A);
+        runner_->init(A, comm);
       }
 
       if (solverInfo.info() > 0)
diff --git a/src/amdis/linearalgebra/LinearSolverInterface.hpp b/src/amdis/linearalgebra/LinearSolverInterface.hpp
index 4e0474bf..ac5201d4 100644
--- a/src/amdis/linearalgebra/LinearSolverInterface.hpp
+++ b/src/amdis/linearalgebra/LinearSolverInterface.hpp
@@ -20,11 +20,15 @@
 namespace AMDiS
 {
   /// Abstract base class for linear solvers
-  template <class Mat, class Sol, class Rhs = Sol>
+  template <class Traits>
   class LinearSolverInterface
   {
   protected:
-    using RunnerBase = RunnerInterface<Mat, Sol, Rhs>;
+    using RunnerBase = RunnerInterface<Traits>;
+    using Mat = typename Traits::Mat;
+    using Sol = typename Traits::Sol;
+    using Rhs = typename Traits::Rhs;
+    using Comm = typename Traits::Comm;
 
   public:
     /// Destructor.
@@ -40,9 +44,9 @@ namespace AMDiS
      *  \p x     A [block-]vector for the unknown components.
      *  \p b     A [block-]vector for the right-hand side of the linear system.
      **/
-    void solve(Mat const& A, Sol& x, Rhs const& b, SolverInfo& solverInfo)
+    void solve(Mat const& A, Sol& x, Rhs const& b, Comm& comm, SolverInfo& solverInfo)
     {
-      solveImpl(A, x, b, solverInfo);
+      solveImpl(A, x, b, comm, solverInfo);
     }
 
     // return the runner/worker corresponding to this solver (optional)
@@ -50,7 +54,7 @@ namespace AMDiS
 
   private:
     /// main methods that all solvers must implement
-    virtual void solveImpl(Mat const& A, Sol& x, Rhs const& b, SolverInfo& solverInfo) = 0;
+    virtual void solveImpl(Mat const& A, Sol& x, Rhs const& b, Comm& comm, SolverInfo& solverInfo) = 0;
   };
 
 
diff --git a/src/amdis/linearalgebra/PreconditionerInterface.hpp b/src/amdis/linearalgebra/PreconditionerInterface.hpp
index 512b924c..ee1388f0 100644
--- a/src/amdis/linearalgebra/PreconditionerInterface.hpp
+++ b/src/amdis/linearalgebra/PreconditionerInterface.hpp
@@ -5,9 +5,13 @@
 namespace AMDiS
 {
   /// Interface for Preconditioner types
-  template <class Mat, class Sol, class Rhs = Sol>
+  template <class Traits>
   struct PreconditionerInterface
   {
+    using Mat = typename Traits::Mat;
+    using Sol = typename Traits::Sol;
+    using Rhs = typename Traits::Rhs;
+
     /// Virtual destructor.
     virtual ~PreconditionerInterface() = default;
 
diff --git a/src/amdis/linearalgebra/RunnerInterface.hpp b/src/amdis/linearalgebra/RunnerInterface.hpp
index 4aebd884..7ba48fea 100644
--- a/src/amdis/linearalgebra/RunnerInterface.hpp
+++ b/src/amdis/linearalgebra/RunnerInterface.hpp
@@ -8,18 +8,22 @@ namespace AMDiS
   class SolverInfo;
 
   /// Interface for Runner / Worker types used in solver classes
-  template <class Mat, class Sol, class Rhs = Sol>
+  template <class Traits>
   class RunnerInterface
   {
   protected:
-    using PreconBase = PreconditionerInterface<Mat, Sol, Rhs>;
+    using PreconBase = PreconditionerInterface<Traits>;
+    using Mat = typename Traits::Mat;
+    using Sol = typename Traits::Sol;
+    using Rhs = typename Traits::Rhs;
+    using Comm = typename Traits::Comm;
 
   public:
     /// virtual destructor
     virtual ~RunnerInterface() = default;
 
     /// Is called at the beginning of a solution procedure
-    virtual void init(Mat const& A) = 0;
+    virtual void init(Mat const& A, Comm& comm) = 0;
 
     /// Is called at the end of a solution procedure
     virtual void exit() = 0;
diff --git a/src/amdis/linearalgebra/eigen/CMakeLists.txt b/src/amdis/linearalgebra/eigen/CMakeLists.txt
index 2cc5df2e..a7959900 100644
--- a/src/amdis/linearalgebra/eigen/CMakeLists.txt
+++ b/src/amdis/linearalgebra/eigen/CMakeLists.txt
@@ -7,4 +7,5 @@ install(FILES
     PreconConfig.hpp
     SolverConfig.hpp
     SolverCreator.hpp
+    Traits.hpp
 DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/amdis/linearalgebra/eigen)
diff --git a/src/amdis/linearalgebra/eigen/DirectRunner.hpp b/src/amdis/linearalgebra/eigen/DirectRunner.hpp
index f37208b9..fff3dd06 100644
--- a/src/amdis/linearalgebra/eigen/DirectRunner.hpp
+++ b/src/amdis/linearalgebra/eigen/DirectRunner.hpp
@@ -14,13 +14,17 @@ namespace AMDiS
   * \class AMDiS::DirectRunner
   * \brief \implements RunnerInterface for the (external) direct solvers
   */
-  template <template <class> class Solver, class Matrix, class VectorX, class VectorB>
+  template <template <class> class Solver, class Traits>
   class DirectRunner
-      : public RunnerInterface<Matrix, VectorX, VectorB>
+      : public RunnerInterface<Traits>
   {
   protected:
-    using Super = RunnerInterface<Matrix, VectorX, VectorB>;
-    using EigenSolver = Solver<Matrix>;
+    using Super = RunnerInterface<Traits>;
+    using Mat = typename Traits::Mat;
+    using Sol = typename Traits::Sol;
+    using Rhs = typename Traits::Rhs;
+    using Comm = typename Traits::Comm;
+    using EigenSolver = Solver<Mat>;
 
   public:
     /// Constructor.
@@ -31,9 +35,11 @@ namespace AMDiS
       Parameters::get(prefix + "->reuse pattern", reusePattern_);
     }
 
-    /// Implementes \ref RunnerInterface::init()
-    void init(Matrix const& A) override
+    /// Implements \ref RunnerInterface::init()
+    void init(Mat const& A, Comm& comm) override
     {
+      DUNE_UNUSED_PARAMETER(comm);
+
       if (!reusePattern_ || !initialized_) {
         solver_.analyzePattern(A);
         initialized_ = true;
@@ -45,16 +51,17 @@ namespace AMDiS
     }
 
 
-    /// Implementes \ref RunnerInterface::exit()
+    /// Implements \ref RunnerInterface::exit()
     void exit() override {}
 
-    /// Implementes \ref RunnerInterface::solve()
-    int solve(Matrix const& A, VectorX& x, VectorB const& b,
-              SolverInfo& solverInfo) override
+    /// Implements \ref RunnerInterface::solve()
+    int solve(Mat const& A, Sol& x, Rhs const& b, SolverInfo& solverInfo) override
     {
+      DUNE_UNUSED_PARAMETER(A);
+
       x = solver_.solve(b);
 
-      auto r = VectorB(b);
+      auto r = Rhs(b);
       if (x.norm() != 0)
         r -= A * x;
 
diff --git a/src/amdis/linearalgebra/eigen/IterativeRunner.hpp b/src/amdis/linearalgebra/eigen/IterativeRunner.hpp
index 95aaab1f..c24fda9c 100644
--- a/src/amdis/linearalgebra/eigen/IterativeRunner.hpp
+++ b/src/amdis/linearalgebra/eigen/IterativeRunner.hpp
@@ -9,12 +9,16 @@
 
 namespace AMDiS
 {
-  template <class IterativeSolver, class Matrix, class VectorX, class VectorB>
+  template <class IterativeSolver, class Traits>
   class IterativeRunner
-      : public RunnerInterface<Matrix, VectorX, VectorB>
+      : public RunnerInterface<Traits>
   {
     using SolverCfg = SolverConfig<IterativeSolver>;
     using PreconCfg = PreconConfig<typename IterativeSolver::Preconditioner>;
+    using Mat = typename Traits::Mat;
+    using Sol = typename Traits::Sol;
+    using Rhs = typename Traits::Rhs;
+    using Comm = typename Traits::Comm;
 
   public:
     IterativeRunner(std::string const& prefix)
@@ -26,9 +30,11 @@ namespace AMDiS
     }
 
 
-    /// Implementes \ref RunnerInterface::init()
-    void init(Matrix const& A) override
+    /// Implements \ref RunnerInterface::init()
+    void init(Mat const& A, Comm& comm) override
     {
+      DUNE_UNUSED_PARAMETER(comm);
+
       if (!reusePattern_ || !initialized_) {
         solver_.analyzePattern(A);
         initialized_ = true;
@@ -39,17 +45,18 @@ namespace AMDiS
         "Error in solver.compute(matrix)");
     }
 
-    /// Implementes \ref RunnerInterface::exit()
+    /// Implements \ref RunnerInterface::exit()
     void exit() override {}
 
-    /// Implementes \ref RunnerInterface::solve()
-    int solve(Matrix const& A, VectorX& x, VectorB const& b,
-              SolverInfo& solverInfo) override
+    /// Implements \ref RunnerInterface::solve()
+    int solve(Mat const& A, Sol& x, Rhs const& b, SolverInfo& solverInfo) override
     {
+      DUNE_UNUSED_PARAMETER(A);
+
       solver_.setTolerance(solverInfo.relTolerance());
       x = solver_.solveWithGuess(b, x);
 
-      auto r = VectorB(b);
+      auto r = Rhs(b);
       if (x.norm() != 0)
         r -= A * x;
 
diff --git a/src/amdis/linearalgebra/eigen/SolverCreator.hpp b/src/amdis/linearalgebra/eigen/SolverCreator.hpp
index 8d283837..edf06e55 100644
--- a/src/amdis/linearalgebra/eigen/SolverCreator.hpp
+++ b/src/amdis/linearalgebra/eigen/SolverCreator.hpp
@@ -11,24 +11,27 @@
 
 #include <amdis/CreatorMap.hpp>
 #include <amdis/Initfile.hpp>
+#include <amdis/Output.hpp>
 
 #include <amdis/linearalgebra/LinearSolver.hpp>
 #include <amdis/linearalgebra/eigen/DirectRunner.hpp>
 #include <amdis/linearalgebra/eigen/IterativeRunner.hpp>
+#include <amdis/linearalgebra/eigen/Traits.hpp>
 
 namespace AMDiS
 {
-  template <class Matrix, class VectorX, class VectorB, template <class> class IterativeSolver>
+  template <class Traits, template <class> class IterativeSolver>
   struct IterativeSolverCreator
-      : public CreatorInterfaceName<LinearSolverInterface<Matrix, VectorX, VectorB>>
+      : public CreatorInterfaceName<LinearSolverInterface<Traits>>
   {
     template <class Precon>
     using SolverCreator
-      = typename LinearSolver<Matrix, VectorX, VectorB,
-          IterativeRunner<IterativeSolver<Precon>, Matrix, VectorX, VectorB>>::Creator;
+      = typename LinearSolver<Traits,
+          IterativeRunner<IterativeSolver<Precon>, Traits>>::Creator;
 
-    using SolverBase = LinearSolverInterface<Matrix, VectorX, VectorB>;
-    using Scalar = typename Matrix::Scalar;
+    using SolverBase = LinearSolverInterface<Traits>;
+    using Mat = typename Traits::Mat;
+    using Scalar = typename Mat::Scalar;
 
     std::unique_ptr<SolverBase> createWithString(std::string prefix) override
     {
@@ -68,17 +71,16 @@ namespace AMDiS
       Parameters::get(prefix + "->precon->ordering", ordering);
 
       if (ordering == "amd") {
-        using AMD = Eigen::AMDOrdering<typename Matrix::StorageIndex>;
+        using AMD = Eigen::AMDOrdering<typename Mat::StorageIndex>;
         return IncompleteCholesky<AMD>{}.createWithString(prefix);
       }
       else {
-        using NATURAL = Eigen::NaturalOrdering<typename Matrix::StorageIndex>;
+        using NATURAL = Eigen::NaturalOrdering<typename Mat::StorageIndex>;
         return IncompleteCholesky<NATURAL>{}.createWithString(prefix);
       }
     }
   };
 
-
   /// Adds default creators for linear solvers based on `Eigen::SparseMatrix`.
   /**
    * Adds creators for full-matrix aware solvers.
@@ -90,36 +92,37 @@ namespace AMDiS
    * - *umfpack*: external UMFPACK solver, \see Eigen::UmfPackLU
    * - *superlu*: external SparseLU solver, \see Eigen::SparseLU
    **/
-  template <class T, int O, class VectorX, class VectorB>
-  class DefaultCreators<LinearSolverInterface<Eigen::SparseMatrix<T,O>, VectorX, VectorB>>
+  template <class Traits>
+  class DefaultCreators< LinearSolverInterface<Traits> >
   {
-    using Matrix = Eigen::SparseMatrix<T,O>;
-    using SolverBase = LinearSolverInterface<Matrix, VectorX, VectorB>;
+    using Mat = typename Traits::Mat;
+
+    using SolverBase = LinearSolverInterface<Traits>;
 
     template <template <class> class IterativeSolver>
     using SolverCreator
-      = IterativeSolverCreator<Matrix, VectorX, VectorB, IterativeSolver>;
+      = IterativeSolverCreator<Traits, IterativeSolver>;
 
     template <template <class> class DirectSolver>
     using DirectSolverCreator
-      = typename LinearSolver<Matrix, VectorX, VectorB,
-          DirectRunner<DirectSolver, Matrix, VectorX, VectorB>>::Creator;
+      = typename LinearSolver<Traits,
+          DirectRunner<DirectSolver, Traits>>::Creator;
 
     //@{
     template <class Precon>
-    using CG = Eigen::ConjugateGradient<Matrix, Eigen::Lower|Eigen::Upper, Precon>;
+    using CG = Eigen::ConjugateGradient<Mat, Eigen::Lower|Eigen::Upper, Precon>;
 
     template <class Precon>
-    using BCGS = Eigen::BiCGSTAB<Matrix, Precon>;
+    using BCGS = Eigen::BiCGSTAB<Mat, Precon>;
 
     template <class Precon>
-    using MINRES = Eigen::MINRES<Matrix, Eigen::Lower|Eigen::Upper, Precon>;
+    using MINRES = Eigen::MINRES<Mat, Eigen::Lower|Eigen::Upper, Precon>;
 
     template <class Precon>
-    using GMRES = Eigen::GMRES<Matrix, Precon>;
+    using GMRES = Eigen::GMRES<Mat, Precon>;
 
     template <class Precon>
-    using DGMRES = Eigen::DGMRES<Matrix, Precon>;
+    using DGMRES = Eigen::DGMRES<Mat, Precon>;
     // @}
 
     using Map = CreatorMap<SolverBase>;
diff --git a/src/amdis/linearalgebra/eigen/Traits.hpp b/src/amdis/linearalgebra/eigen/Traits.hpp
new file mode 100644
index 00000000..ae8cd211
--- /dev/null
+++ b/src/amdis/linearalgebra/eigen/Traits.hpp
@@ -0,0 +1,15 @@
+#pragma once
+
+#include <amdis/linearalgebra/Common.hpp>
+
+namespace AMDiS
+{
+  /** Traits class for a linear solver for the system AX=B using an FE space described by a dune-functions Basis
+   *  Contains typedefs specific to the EIGEN backend.
+   */
+  template <class A, class X, class B, class Basis>
+  class SolverTraits
+      : public SolverTraitsBase<A,X,B,Basis>
+  {};
+
+} // end namespace AMDiS
diff --git a/src/amdis/linearalgebra/istl/CMakeLists.txt b/src/amdis/linearalgebra/istl/CMakeLists.txt
index f11fd2db..7463442b 100644
--- a/src/amdis/linearalgebra/istl/CMakeLists.txt
+++ b/src/amdis/linearalgebra/istl/CMakeLists.txt
@@ -1,5 +1,8 @@
 install(FILES
+    Communication.hpp
+    Communication.inc.hpp
     Constraints.hpp
+    Creators.hpp
     DirectRunner.hpp
     DOFMatrix.hpp
     DOFVector.hpp
@@ -7,4 +10,5 @@ install(FILES
     ISTL_Preconditioner.hpp
     ISTL_Solver.hpp
     ISTLRunner.hpp
+    Traits.hpp
 DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/amdis/linearalgebra/istl)
diff --git a/src/amdis/linearalgebra/istl/Communication.hpp b/src/amdis/linearalgebra/istl/Communication.hpp
new file mode 100644
index 00000000..eb63684f
--- /dev/null
+++ b/src/amdis/linearalgebra/istl/Communication.hpp
@@ -0,0 +1,105 @@
+#pragma once
+
+#include <memory>
+#include <ostream>
+#include <set>
+#include <string>
+#include <utility>
+
+#include <dune/common/version.hh>
+#include <dune/istl/owneroverlapcopy.hh>
+#include <dune/istl/solvercategory.hh>
+
+#include <amdis/functions/GlobalIdSet.hpp>
+
+namespace AMDiS
+{
+
+#if HAVE_MPI
+  /// Implementation class for ISTL-specific communication to be used in parallel solvers
+  template <class Basis>
+  class ISTLCommunication
+      : public Dune::OwnerOverlapCopyCommunication<typename GlobalBasisIdSet<Basis>::IdType, typename Basis::size_type>
+  {
+    using GlobalCommIdType = typename GlobalBasisIdSet<Basis>::IdType;
+    using LocalCommIdType = typename Basis::size_type;
+
+    using Self = ISTLCommunication;
+    using Super = Dune::OwnerOverlapCopyCommunication<GlobalCommIdType, LocalCommIdType>;
+
+    using GridView = typename Basis::GridView;
+    using Grid = typename GridView::Grid;
+    using Element = typename GridView::template Codim<0>::Entity;
+    using IdSet = typename Grid::GlobalIdSet;
+    using IdType = typename IdSet::IdType;
+    using EntitySet = std::set<IdType>;
+    using Comm = typename Dune::MPIHelper::MPICommunicator;
+    using SolverType = typename Dune::SolverCategory::Category;
+
+  public:
+    /**
+     * Constructor. Takes the global basis, an MPI communicator and the ISTL solver type
+     *
+     * \param basis   Global basis associated to the solvers' matrices and vectors
+     * \param comm    MPI communicator of the group containing the distributed matrices and vectors
+     * \param cat     Category of the solver used with this communicator, one of
+     *                Dune::SolverCategory::Category::sequential, overlapping, nonoverlapping
+     **/
+    ISTLCommunication(Basis const& basis, Comm const& comm, SolverType cat)
+      : Super(comm, cat)
+    {
+      if (cat != SolverType::sequential)
+      {
+        auto& pis = this->indexSet();
+        buildParallelIndexSet(basis, pis);
+        auto& ris = this->remoteIndices();
+        ris.setIndexSets(pis,pis,comm);
+        ris.template rebuild<true>();
+      }
+    }
+
+  private:
+    /// Builds the parallel index set containing all DoFs of the basis
+    void buildParallelIndexSet(Basis const& basis, typename Super::PIS& pis);
+
+  public:
+    /**
+     * ISTLCommunication creator function. Takes the global basis and the solver's initfile prefix
+     * and returns a unique pointer to the ISTLCommunication object.
+     * Deduces the category of the solver used from the initfile and basis
+     *
+     * \param basis   Global basis associated to the solvers' matrices and vectors
+     * \param prefix  Solver prefix used in the initfile, usually "<problem name>->solver"
+     **/
+    static std::unique_ptr<Self> create(Basis const& basis, std::string const& prefix);
+  };
+
+#else // !HAVE_MPI
+
+  /// Dummy implementation for ISTL-specific communication when no MPI is found
+  template <class Basis>
+  class ISTLCommunication
+      : public DefaultCommunication<Basis>
+  {
+    using Self = ISTLCommunication;
+
+  public:
+    ISTLCommunication() = default;
+
+    Dune::SolverCategory::Category category() const
+    {
+      return Dune::SolverCategory::Category::sequential;
+    }
+
+    static std::unique_ptr<Self> create(Basis const& basis, std::string const& prefix)
+    {
+      DUNE_UNUSED_PARAMETER(basis);
+      DUNE_UNUSED_PARAMETER(prefix);
+      return std::make_unique<Self>();
+    }
+  };
+#endif
+
+} // end namespace AMDiS
+
+#include <amdis/linearalgebra/istl/Communication.inc.hpp>
diff --git a/src/amdis/linearalgebra/istl/Communication.inc.hpp b/src/amdis/linearalgebra/istl/Communication.inc.hpp
new file mode 100644
index 00000000..299a1ce3
--- /dev/null
+++ b/src/amdis/linearalgebra/istl/Communication.inc.hpp
@@ -0,0 +1,139 @@
+#pragma once
+
+#include <dune/common/parallel/mpihelper.hh>
+
+#include <dune/grid/common/gridenums.hh>
+
+#include <amdis/utility/UniqueBorderPartition.hpp>
+#include <amdis/Initfile.hpp>
+#include <amdis/Output.hpp>
+
+namespace AMDiS {
+
+#if HAVE_MPI
+
+template <class Basis>
+std::unique_ptr< ISTLCommunication<Basis> > ISTLCommunication<Basis>
+::create(Basis const& basis, std::string const& prefix)
+{
+  std::string category = "default";
+  Parameters::get(prefix + "->category", category);
+  SolverType cat;
+  auto const& gv = basis.gridView();
+  int nProcs = gv.comm().size();
+
+  if (category == "default")
+  {
+    if (nProcs == 1)
+    {
+      cat = SolverType::sequential;
+    }
+    else
+    {
+      // Use overlapping solver if grid has overlap
+      if (gv.overlapSize(0) > 0)
+        cat = SolverType::overlapping;
+      else
+      {
+        // TODO(FM): Remove once nonoverlapping solvers are supported
+        warning("Nonoverlapping solvers are currently not supported. "
+          "Overlapping solver category chosen for grid with no overlap\n");
+        cat = SolverType::overlapping;
+        // cat = SolverType::nonoverlapping;
+      }
+    }
+  }
+  else if (category != "sequential" && nProcs == 1)
+  {
+    warning("Only one process detected. Solver category set to sequential\n");
+    cat = SolverType::sequential;
+  }
+  else if (category == "sequential")
+  {
+    test_exit(nProcs == 1, "Solver category sequential is not supported in parallel\n");
+    cat = SolverType::sequential;
+  }
+  else if (category == "overlapping")
+  {
+    if (gv.overlapSize(0) == 0)
+      warning("Overlapping solver category chosen for grid with no overlap\n");
+    cat = SolverType::overlapping;
+  }
+  else if (category == "nonoverlapping")
+  {
+    error_exit("Nonoverlapping solvers are currently not supported.");
+    cat = SolverType::nonoverlapping;
+  }
+  else
+  {
+    error_exit("Unknown solver category\n");
+  }
+
+  return std::make_unique<Self>(basis, Dune::MPIHelper::getCommunicator(), cat);
+}
+
+template <class Basis>
+void ISTLCommunication<Basis>
+::buildParallelIndexSet(Basis const& basis, typename Super::PIS& pis)
+{
+  using Attribute = typename Dune::OwnerOverlapCopyAttributeSet::AttributeSet;
+  using PType = Dune::PartitionType;
+  using LI = typename Super::PIS::LocalIndex;
+
+  auto const& gv = basis.gridView();
+
+  // make disjoint partition of border entities
+  EntitySet borderEntities;
+  using DataHandle = UniqueBorderPartitionDataHandle<Grid>;
+  DataHandle handle(gv.comm().rank(), borderEntities, gv.grid().globalIdSet());
+  gv.communicate(handle,
+    Dune::InterfaceType::InteriorBorder_InteriorBorder_Interface,
+    Dune::CommunicationDirection::ForwardCommunication);
+
+  if (gv.overlapSize(0) + gv.ghostSize(0) == 0)
+    // TODO(FM): Add support for this special case
+    error_exit("Using grids with ghostSize(0) + overlapSize(0) == 0 is not supported\n");
+
+  auto lv = basis.localView();
+  GlobalBasisIdSet<Basis> dofIdSet(basis);
+
+  pis.beginResize();
+  for (auto const& e : Dune::elements(gv))
+  {
+    lv.bind(e);
+    dofIdSet.bind(e);
+    for (std::size_t i = 0; i < dofIdSet.size(); ++i)
+    {
+      LocalCommIdType localId = lv.index(i);
+      GlobalCommIdType globalId = dofIdSet.id(i);
+      PType attribute = dofIdSet.partitionType(i);
+      switch (attribute)
+      {
+      case PType::InteriorEntity:
+        pis.add(globalId, LI(localId, Attribute::owner, true));
+        break;
+      case PType::BorderEntity:
+        // mark border entity as owned iff it is part of the process's borderEntities set
+        if (borderEntities.count(dofIdSet.entityId(i)) == 1)
+          pis.add(globalId, LI(localId, Attribute::owner, true));
+        else
+          pis.add(globalId, LI(localId, Attribute::overlap, true));
+        break;
+      case PType::OverlapEntity:
+      case PType::FrontEntity:
+        pis.add(globalId, LI(localId, Attribute::overlap, true));
+        break;
+      case PType::GhostEntity:
+        pis.add(globalId, LI(localId, Attribute::copy, true));
+        break;
+      }
+    }
+    dofIdSet.unbind();
+    lv.unbind();
+  }
+  pis.endResize();
+}
+
+#endif
+
+} // end namespace AMDiS
diff --git a/src/amdis/linearalgebra/istl/Creators.hpp b/src/amdis/linearalgebra/istl/Creators.hpp
new file mode 100644
index 00000000..615d2f55
--- /dev/null
+++ b/src/amdis/linearalgebra/istl/Creators.hpp
@@ -0,0 +1,97 @@
+#pragma once
+
+#include <memory>
+
+#include <dune/istl/operators.hh>
+#include <dune/istl/scalarproducts.hh>
+#include <dune/istl/solvercategory.hh>
+
+#if HAVE_MPI
+#include <dune/istl/novlpschwarz.hh>
+#include <dune/istl/schwarz.hh>
+#endif
+
+#include <amdis/Output.hpp>
+
+namespace AMDiS
+{
+  /// Creator to create ScalarProduct objects
+  template <class X>
+  class ISTLScalarProductCreator
+  {
+    using Interface = Dune::ScalarProduct<X>;
+
+  public:
+    template <class C>
+    static std::unique_ptr<Interface> create(Dune::SolverCategory::Category cat, C const& comm)
+    {
+      switch (cat)
+      {
+        case Dune::SolverCategory::Category::sequential :
+          return std::make_unique< Dune::SeqScalarProduct<X> >();
+#if HAVE_MPI
+        case Dune::SolverCategory::Category::overlapping :
+          return std::make_unique< Dune::OverlappingSchwarzScalarProduct<X,C> >(comm);
+        case Dune::SolverCategory::Category::nonoverlapping :
+          return std::make_unique< Dune::NonoverlappingSchwarzScalarProduct<X,C> >(comm);
+#endif
+        default:
+          error_exit("Invalid solver category for scalar product\n");
+          return nullptr; // avoid warnings
+      }
+    }
+  };
+
+  /// Creator to create Linear Operator objects
+  template <class A, class X, class B>
+  class ISTLLinearOperatorCreator
+  {
+    using Interface = Dune::AssembledLinearOperator<A,X,B>;
+
+  public:
+    template <class C>
+    static std::unique_ptr<Interface> create(Dune::SolverCategory::Category cat, A const& mat, C const& comm)
+    {
+      switch (cat)
+      {
+        case Dune::SolverCategory::Category::sequential :
+          return std::make_unique< Dune::MatrixAdapter<A,X,B> >(mat);
+#if HAVE_MPI
+        case Dune::SolverCategory::Category::overlapping :
+          return std::make_unique< Dune::OverlappingSchwarzOperator<A,X,B,C> >(mat, comm);
+        case Dune::SolverCategory::Category::nonoverlapping :
+          return std::make_unique< Dune::NonoverlappingSchwarzOperator<A,X,B,C> >(mat, comm);
+#endif
+        default:
+          error_exit("Invalid solver category for linear operator\n");
+          return nullptr; // avoid warnings
+      }
+    }
+  };
+
+  /// Creator to create parallel Preconditioners
+  template <class X, class B>
+  class ISTLParallelPreconditionerCreator
+  {
+    using P = Dune::Preconditioner<X,B>;
+
+  public:
+    template <class C>
+    static std::unique_ptr<P> create(Dune::SolverCategory::Category cat, P& prec, C const& comm)
+    {
+      switch (cat)
+      {
+#if HAVE_MPI
+        case Dune::SolverCategory::Category::overlapping :
+          return std::make_unique< Dune::BlockPreconditioner<X,B,C> >(prec, comm);
+        case Dune::SolverCategory::Category::nonoverlapping :
+          return std::make_unique< Dune::NonoverlappingBlockPreconditioner<C,P> >(prec, comm);
+#endif
+        default:
+          error_exit("Invalid solver category for parallel preconditioner\n");
+          return nullptr; // avoid warnings
+      }
+    }
+  };
+
+} // end namespace AMDiS
diff --git a/src/amdis/linearalgebra/istl/DirectRunner.hpp b/src/amdis/linearalgebra/istl/DirectRunner.hpp
index 6a3f7852..da7977e8 100644
--- a/src/amdis/linearalgebra/istl/DirectRunner.hpp
+++ b/src/amdis/linearalgebra/istl/DirectRunner.hpp
@@ -5,9 +5,10 @@
 
 #include <dune/common/ftraits.hh>
 
-#include <amdis/Output.hpp>
+#include <amdis/linearalgebra/istl/Fwd.hpp>
 #include <amdis/linearalgebra/RunnerInterface.hpp>
 #include <amdis/linearalgebra/SolverInfo.hpp>
+#include <amdis/Output.hpp>
 
 namespace AMDiS
 {
@@ -16,14 +17,17 @@ namespace AMDiS
   * \class AMDiS::DirectRunner
   * \brief \implements RunnerInterface for the (external) direct solvers
   */
-  template <template <class> class Solver, class Mat, class Sol, class Rhs>
+  template <template <class> class Solver, class Traits>
   class DirectRunner
-      : public RunnerInterface<Mat, Sol, Rhs>
+      : public RunnerInterface<Traits>
   {
   protected:
-    using Super = RunnerInterface<Mat, Sol, Rhs>;
+    using Super = RunnerInterface<Traits>;
+    using Mat = typename Traits::Mat;
+    using Sol = typename Traits::Sol;
+    using Rhs = typename Traits::Rhs;
+    using Comm = typename Traits::Comm;
     using BaseSolver  = Dune::InverseOperator<Sol, Rhs>;
-    using ISTLSolver = Solver<Mat>;
 
   public:
     /// Constructor.
@@ -31,22 +35,24 @@ namespace AMDiS
       : solverCreator_(prefix)
     {}
 
-    /// Implementes \ref RunnerInterface::init()
-    void init(Mat const& A) override
+    /// Implements \ref RunnerInterface::init()
+    void init(Mat const& A, Comm& comm) override
     {
+      DUNE_UNUSED_PARAMETER(comm);
       solver_ = solverCreator_.create(A);
     }
 
-    /// Implementes \ref RunnerInterface::exit()
+    /// Implements \ref RunnerInterface::exit()
     void exit() override
     {
       solver_.reset();
     }
 
-    /// Implementes \ref RunnerInterface::solve()
-    int solve(Mat const& A, Sol& x, Rhs const& b,
-              SolverInfo& solverInfo) override
+    /// Implements \ref RunnerInterface::solve()
+    int solve(Mat const& A, Sol& x, Rhs const& b, SolverInfo& solverInfo) override
     {
+      DUNE_UNUSED_PARAMETER(A);
+
       // storing some statistics
       Dune::InverseOperatorResult statistics;
 
diff --git a/src/amdis/linearalgebra/istl/ISTLRunner.hpp b/src/amdis/linearalgebra/istl/ISTLRunner.hpp
index 24df9b9b..629679cb 100644
--- a/src/amdis/linearalgebra/istl/ISTLRunner.hpp
+++ b/src/amdis/linearalgebra/istl/ISTLRunner.hpp
@@ -1,22 +1,25 @@
 #pragma once
 
-#include <dune/istl/preconditioner.hh>
+#include <dune/common/version.hh>
+#include <dune/istl/solvercategory.hh>
 
-#include <amdis/linearalgebra/RunnerInterface.hpp>
-#include <amdis/linearalgebra/SolverInfo.hpp>
 #include <amdis/linearalgebra/istl/Fwd.hpp>
 #include <amdis/linearalgebra/istl/ISTLPreconCreatorInterface.hpp>
+#include <amdis/linearalgebra/RunnerInterface.hpp>
+#include <amdis/linearalgebra/SolverInfo.hpp>
+#include <amdis/Environment.hpp>
+#include <amdis/Output.hpp>
 
 namespace AMDiS
 {
-  template <class ISTLSolver, class Matrix, class VectorX, class VectorB>
+  template <class ISTLSolver, class Traits>
   class ISTLRunner
-      : public RunnerInterface<Matrix, VectorX, VectorB>
+      : public RunnerInterface<Traits>
   {
-    using LinOperator = Dune::MatrixAdapter<Matrix, VectorX, VectorB>;
-    using BaseSolver  = Dune::InverseOperator<VectorX, VectorB>;
-    using BasePrecon  = Dune::Preconditioner<VectorX, VectorB>;
-    using ISTLPreconCreator  = ISTLPreconCreatorInterface<Matrix, VectorX, VectorB>;
+    using Mat = typename Traits::Mat;
+    using Sol = typename Traits::Sol;
+    using Rhs = typename Traits::Rhs;
+    using ISTLPreconCreator  = ISTLPreconCreatorInterface<Mat, Sol, Rhs>;
 
   public:
     ISTLRunner(std::string const& prefix)
@@ -26,31 +29,45 @@ namespace AMDiS
     }
 
 
-    /// Implementes \ref RunnerInterface::init()
-    void init(Matrix const& A) override
+    /// Implements \ref RunnerInterface::init()
+    void init(Mat const& A, typename Traits::Comm& comm) override
     {
-      precon_ = preconCreator_->create(A);
-      linOperator_ = std::make_shared<LinOperator>(A);
-      solver_ = solverCreator_.create(*linOperator_, *precon_);
+      auto cat = Dune::SolverCategory::category(comm);
+
+      sp_ = Traits::ScalProdCreator::create(cat, comm);
+      if (cat == Dune::SolverCategory::Category::sequential)
+      {
+        precon_ = preconCreator_->create(A);
+      }
+      else
+      {
+        basePrecon_ = preconCreator_->create(A);
+        precon_ = Traits::ParPrecCreator::create(cat, *basePrecon_, comm);
+      }
+      linOperator_ = Traits::LinOpCreator::create(cat, A, comm);
+      solver_ = solverCreator_.create(*linOperator_, *sp_, *precon_);
     }
 
-    /// Implementes \ref RunnerInterface::exit()
+    /// Implements \ref RunnerInterface::exit()
     void exit() override
     {
       solver_.reset();
       linOperator_.reset();
       precon_.reset();
+      basePrecon_.reset();
+      sp_.reset();
     }
 
-    /// Implementes \ref RunnerInterface::solve()
-    int solve(Matrix const& A, VectorX& x, VectorB const& b,
-              SolverInfo& solverInfo) override
+    /// Implements \ref RunnerInterface::solve()
+    int solve(Mat const& A, Sol& x, Rhs const& b, SolverInfo& solverInfo) override
     {
+      DUNE_UNUSED_PARAMETER(A);
+
       // storing some statistics
       Dune::InverseOperatorResult statistics;
 
       // solve the linear system
-      VectorB _b = b;
+      Rhs _b = b;
       solver_->apply(x, _b, statistics);
 
       solverInfo.setRelResidual(statistics.reduction);
@@ -75,6 +92,12 @@ namespace AMDiS
       if (preconName.empty() || preconName == "no")
         preconName = "default";
 
+      // TODO(FM): Find a better test if preconditioner is supported in parallel
+      if (Environment::mpiSize() > 1) {
+        std::set<std::string> tested_precons = {"jacobi", "diag", "default", "richardson"};
+        test_warning(tested_precons.count(preconName) == 1, "Preconditioner {} not supported in parallel.", preconName);
+      }
+
       auto* creator = named(CreatorMap<ISTLPreconCreator>::getCreator(preconName, initFileStr));
       preconCreator_ = creator->createWithString(initFileStr);
       assert(preconCreator_);
@@ -84,9 +107,11 @@ namespace AMDiS
     ISTLSolverCreator<ISTLSolver> solverCreator_;
     std::shared_ptr<ISTLPreconCreator> preconCreator_;
 
-    std::shared_ptr<BasePrecon>   precon_;
-    std::shared_ptr<LinOperator>  linOperator_;
-    std::shared_ptr<BaseSolver>   solver_;
+    std::shared_ptr<typename Traits::ScalProd> sp_;
+    std::shared_ptr<typename Traits::Prec>     basePrecon_;
+    std::shared_ptr<typename Traits::Prec>     precon_;
+    std::shared_ptr<typename Traits::LinOp>    linOperator_;
+    std::shared_ptr<typename Traits::Solver>   solver_;
   };
 
 } // end namespace AMDiS
diff --git a/src/amdis/linearalgebra/istl/ISTL_Preconditioner.hpp b/src/amdis/linearalgebra/istl/ISTL_Preconditioner.hpp
index 833dbb7f..f2338d05 100644
--- a/src/amdis/linearalgebra/istl/ISTL_Preconditioner.hpp
+++ b/src/amdis/linearalgebra/istl/ISTL_Preconditioner.hpp
@@ -14,13 +14,13 @@ namespace AMDiS
   // creators for preconditioners, depending on matrix-type
   // ---------------------------------------------------------------------------
 
-  template <class Precon, class Matrix>
+  template <class Precon, class Mat>
   struct ISTLPreconCreator
-      : public ISTLPreconCreatorInterface<Matrix, typename Precon::domain_type, typename Precon::range_type>
+      : public ISTLPreconCreatorInterface<Mat, typename Precon::domain_type, typename Precon::range_type>
   {
     using Sol = typename Precon::domain_type;
     using Rhs = typename Precon::range_type;
-    using Super = ISTLPreconCreatorInterface<Matrix, Sol, Rhs>;
+    using Super = ISTLPreconCreatorInterface<Mat, Sol, Rhs>;
     using Self = ISTLPreconCreator;
 
     struct Creator : CreatorInterfaceName<Super>
@@ -38,32 +38,32 @@ namespace AMDiS
     }
 
     using PreconBase = Dune::Preconditioner<Sol, Rhs>;
-    std::unique_ptr<PreconBase> create(Matrix const& A) const override
+    std::unique_ptr<PreconBase> create(Mat const& A) const override
     {
       return createImpl(A, Type<Precon>{});
     }
 
   private:
     template <class P>
-    std::unique_ptr<P> createImpl(Matrix const& A, Type<P>) const
+    std::unique_ptr<P> createImpl(Mat const& A, Type<P>) const
     {
       return std::make_unique<P>(A, iter_, w_);
     }
 
-    std::unique_ptr<Dune::SeqILU<Matrix, Sol, Rhs>>
-    createImpl(Matrix const& A, Type<Dune::SeqILU<Matrix, Sol, Rhs>>) const
+    std::unique_ptr<Dune::SeqILU<Mat, Sol, Rhs>>
+    createImpl(Mat const& A, Type<Dune::SeqILU<Mat, Sol, Rhs>>) const
     {
-      return std::make_unique<Dune::SeqILU<Matrix, Sol, Rhs>>(A, iter_, w_);
+      return std::make_unique<Dune::SeqILU<Mat, Sol, Rhs>>(A, iter_, w_);
     }
 
     std::unique_ptr<Dune::Richardson<Sol, Rhs>>
-    createImpl(Matrix const& /*A*/, Type<Dune::Richardson<Sol, Rhs>>) const
+    createImpl(Mat const& /*A*/, Type<Dune::Richardson<Sol, Rhs>>) const
     {
       return std::make_unique<Dune::Richardson<Sol, Rhs>>(w_);
     }
 
     double w_ = 1.0;
-    int iter_ = 0;
+    int iter_ = 1;
   };
 
 
diff --git a/src/amdis/linearalgebra/istl/ISTL_Solver.hpp b/src/amdis/linearalgebra/istl/ISTL_Solver.hpp
index 82615784..430098ad 100644
--- a/src/amdis/linearalgebra/istl/ISTL_Solver.hpp
+++ b/src/amdis/linearalgebra/istl/ISTL_Solver.hpp
@@ -3,6 +3,7 @@
 #include <memory>
 
 #include <dune/common/classname.hh>
+
 #include <dune/istl/solvers.hh>
 #include <dune/istl/umfpack.hh>
 #include <dune/istl/superlu.hh>
@@ -10,9 +11,12 @@
 #include <amdis/CreatorMap.hpp>
 #include <amdis/Initfile.hpp>
 
-#include <amdis/linearalgebra/istl/Fwd.hpp>
 #include <amdis/linearalgebra/istl/DirectRunner.hpp>
+#include <amdis/linearalgebra/istl/Fwd.hpp>
 #include <amdis/linearalgebra/istl/ISTLRunner.hpp>
+#include <amdis/linearalgebra/istl/Traits.hpp>
+#include <amdis/Environment.hpp>
+#include <amdis/Output.hpp>
 
 namespace AMDiS
 {
@@ -21,27 +25,31 @@ namespace AMDiS
   {
     ISTLSolverCreator(std::string const& prefix)
     {
-      Parameters::get(prefix + "->info", info_);
+      if (Environment::mpiRank() == 0)
+      {
+        info_ = 2;
+        Parameters::get(prefix + "->info", info_);
+      }
       Parameters::get(prefix + "->max iteration", maxIter_);
       Parameters::get(prefix + "->relative tolerance", rTol_);
     }
 
-    template <class LinOperator, class Precon>
-    std::unique_ptr<ISTLSolver> create(LinOperator& A, Precon& P) const
+    template <class LinOperator, class ScalProd, class Precon>
+    std::unique_ptr<ISTLSolver> create(LinOperator& A, ScalProd& sp, Precon& P) const
     {
-      return std::make_unique<ISTLSolver>(A, P, rTol_, maxIter_, info_);
+      return std::make_unique<ISTLSolver>(A, sp, P, rTol_, maxIter_, info_);
     }
 
-    int info_ = 2;
+    int info_ = 0;
     std::size_t maxIter_ = 500;
     double rTol_ = 1.e-6;
   };
 
-  template <class VectorX>
-  struct ISTLSolverCreator<Dune::RestartedGMResSolver<VectorX>, true>
-      : public ISTLSolverCreator<Dune::RestartedGMResSolver<VectorX>, false>
+  template <class Sol>
+  struct ISTLSolverCreator<Dune::RestartedGMResSolver<Sol>, true>
+      : public ISTLSolverCreator<Dune::RestartedGMResSolver<Sol>, false>
   {
-    using ISTLSolver = Dune::RestartedGMResSolver<VectorX>;
+    using ISTLSolver = Dune::RestartedGMResSolver<Sol>;
     using Super = ISTLSolverCreator<ISTLSolver, false>;
 
     ISTLSolverCreator(std::string const& prefix)
@@ -50,20 +58,20 @@ namespace AMDiS
       Parameters::get(prefix + "->restart", restart_);
     }
 
-    template <class LinOperator, class Precon>
-    std::unique_ptr<ISTLSolver> create(LinOperator& A, Precon& P) const
+    template <class LinOperator, class ScalProd, class Precon>
+    std::unique_ptr<ISTLSolver> create(LinOperator& A, ScalProd& sp, Precon& P) const
     {
-      return std::make_unique<ISTLSolver>(A, P, this->rTol_, restart_, this->maxIter_, this->info_);
+      return std::make_unique<ISTLSolver>(A, sp, P, this->rTol_, restart_, this->maxIter_, this->info_);
     }
 
     int restart_ = 30;
   };
 
-  template <class VectorX>
-  struct ISTLSolverCreator<Dune::GeneralizedPCGSolver<VectorX>, true>
-      : public ISTLSolverCreator<Dune::GeneralizedPCGSolver<VectorX>, false>
+  template <class Sol>
+  struct ISTLSolverCreator<Dune::GeneralizedPCGSolver<Sol>, true>
+      : public ISTLSolverCreator<Dune::GeneralizedPCGSolver<Sol>, false>
   {
-    using ISTLSolver = Dune::GeneralizedPCGSolver<VectorX>;
+    using ISTLSolver = Dune::GeneralizedPCGSolver<Sol>;
     using Super = ISTLSolverCreator<ISTLSolver, false>;
 
     ISTLSolverCreator(std::string const& prefix)
@@ -72,10 +80,10 @@ namespace AMDiS
       Parameters::get(prefix + "->restart", restart_);
     }
 
-    template <class LinOperator, class Precon>
-    std::unique_ptr<ISTLSolver> create(LinOperator& A, Precon& P) const
+    template <class LinOperator, class ScalProd, class Precon>
+    std::unique_ptr<ISTLSolver> create(LinOperator& A, ScalProd& sp, Precon& P) const
     {
-      return std::make_unique<ISTLSolver>(A, P, this->rTol_, this->maxIter_, this->info_, restart_);
+      return std::make_unique<ISTLSolver>(A, sp, P, this->rTol_, this->maxIter_, this->info_, restart_);
     }
 
     int restart_ = 30;
@@ -83,16 +91,17 @@ namespace AMDiS
 
 
 #if HAVE_SUITESPARSE_UMFPACK
-  template <class Matrix>
-  struct ISTLSolverCreator<Dune::UMFPack<Matrix>, true>
+  template <class Mat>
+  struct ISTLSolverCreator<Dune::UMFPack<Mat>, true>
   {
-    using Solver = Dune::UMFPack<Matrix>;
+    using Solver = Dune::UMFPack<Mat>;
     ISTLSolverCreator(std::string const& prefix)
     {
+      test_exit(Environment::mpiSize() == 1, "UMFPack solver cannot be used in parallel");
       Parameters::get(prefix + "->info", verbose_);
     }
 
-    std::unique_ptr<Solver> create(Matrix const& A) const
+    std::unique_ptr<Solver> create(Mat const& A) const
     {
       return std::make_unique<Solver>(A, verbose_);
     }
@@ -103,12 +112,13 @@ namespace AMDiS
 #endif
 
 #if HAVE_SUPERLU
-  template <class Matrix>
-  struct ISTLSolverCreator<Dune::SuperLU<Matrix>, true>
+  template <class Mat>
+  struct ISTLSolverCreator<Dune::SuperLU<Mat>, true>
   {
-    using Solver = Dune::SuperLU<Matrix>;
+    using Solver = Dune::SuperLU<Mat>;
     ISTLSolverCreator(std::string const& prefix)
     {
+      test_exit(Environment::mpiSize() == 1, "SuperLU solver cannot be used in parallel");
       int info = 2;
       Parameters::get(prefix + "->info", info);
       verbose_ = (info != 0);
@@ -116,7 +126,7 @@ namespace AMDiS
       Parameters::get(prefix + "->reuse vector", reuseVector_);
     }
 
-    std::unique_ptr<Solver> create(Matrix const& A) const
+    std::unique_ptr<Solver> create(Mat const& A) const
     {
       return std::make_unique<Solver>(A, verbose_, reuseVector_);
     }
@@ -138,43 +148,44 @@ namespace AMDiS
    * - *umfpack*: external UMFPACK solver, \see Dune::UMFPack
    * - *superlu*: external SuperLU solver, \see Dune::SuperLU
    **/
-  template <class Block, class Alloc, class VectorX, class VectorB>
-  class DefaultCreators<LinearSolverInterface<Dune::BCRSMatrix<Block,Alloc>, VectorX, VectorB>>
+  template <class Traits>
+  class DefaultCreators< LinearSolverInterface<Traits> >
   {
-    using Matrix = Dune::BCRSMatrix<Block,Alloc>;
-    using FTraits = Dune::FieldTraits<typename Matrix::field_type>;
-    using SolverBase = LinearSolverInterface<Matrix, VectorX, VectorB>;
+    using Mat = typename Traits::Mat;
+    using Sol = typename Traits::Sol;
+    using FTraits = Dune::FieldTraits<typename Mat::field_type>;
+    using SolverBase = LinearSolverInterface<Traits>;
 
     template <class Solver>
     using SolverCreator
-      = typename LinearSolver<Matrix, VectorX, VectorB,
-          ISTLRunner<Solver, Matrix, VectorX, VectorB>>::Creator;
+      = typename LinearSolver<Traits,
+          ISTLRunner<Solver, Traits>>::Creator;
 
     template <template <class M> class Solver>
     using DirectSolverCreator
-      = typename LinearSolver<Matrix, VectorX, VectorB,
-          DirectRunner<Solver, Matrix, VectorX, VectorB>>::Creator;
+      = typename LinearSolver<Traits,
+          DirectRunner<Solver, Traits>>::Creator;
 
     using Map = CreatorMap<SolverBase>;
 
   public:
     static void init()
     {
-      auto cg = new SolverCreator<Dune::CGSolver<VectorX>>;
+      auto cg = new SolverCreator<Dune::CGSolver<Sol>>;
       Map::addCreator("cg", cg);
 
-      auto bicgstab = new SolverCreator<Dune::BiCGSTABSolver<VectorX>>;
+      auto bicgstab = new SolverCreator<Dune::BiCGSTABSolver<Sol>>;
       Map::addCreator("bicgstab", bicgstab);
       Map::addCreator("bcgs", bicgstab);
 
-      auto minres = new SolverCreator<Dune::MINRESSolver<VectorX>>;
+      auto minres = new SolverCreator<Dune::MINRESSolver<Sol>>;
       Map::addCreator("minres", minres);
 
-      auto gmres = new SolverCreator<Dune::RestartedGMResSolver<VectorX>>;
+      auto gmres = new SolverCreator<Dune::RestartedGMResSolver<Sol>>;
       Map::addCreator("gmres", gmres);
 
       // Generalized preconditioned conjugate gradient solver.
-      auto fcg = new SolverCreator<Dune::GeneralizedPCGSolver<VectorX>>;
+      auto fcg = new SolverCreator<Dune::GeneralizedPCGSolver<Sol>>;
       Map::addCreator("fcg", fcg);
 
       // default iterative solver
@@ -201,7 +212,7 @@ namespace AMDiS
       Map::addCreator("superlu", superlu);
 #endif
 
-    // default direct solvers
+      // default direct solvers
 #if HAVE_SUITESPARSE_UMFPACK
       Map::addCreator("direct", umfpack);
 #elif HAVE_SUPERLU
diff --git a/src/amdis/linearalgebra/istl/Traits.hpp b/src/amdis/linearalgebra/istl/Traits.hpp
new file mode 100644
index 00000000..f7e73e8b
--- /dev/null
+++ b/src/amdis/linearalgebra/istl/Traits.hpp
@@ -0,0 +1,26 @@
+#pragma once
+
+#include <amdis/linearalgebra/istl/Communication.hpp>
+#include <amdis/linearalgebra/istl/Creators.hpp>
+#include <amdis/linearalgebra/Common.hpp>
+
+namespace AMDiS
+{
+  /** Traits class for a linear solver for the system AX=B using an FE space described by a dune-functions Basis
+   *  Contains typedefs specific to the ISTL backend.
+   */
+  template <class A, class X, class B, class Basis>
+  class SolverTraits : public SolverTraitsBase<A,X,B,Basis>
+  {
+  public:
+    using Comm            = ISTLCommunication<Basis>;
+    using ScalProd        = Dune::ScalarProduct<X>;
+    using LinOp           = Dune::AssembledLinearOperator<A, X, B>;
+    using Solver          = Dune::InverseOperator<X, B>;
+    using Prec            = Dune::Preconditioner<X, B>;
+    using ScalProdCreator = ISTLScalarProductCreator<X>;
+    using ParPrecCreator  = ISTLParallelPreconditionerCreator<X, B>;
+    using LinOpCreator    = ISTLLinearOperatorCreator<A, X, B>;
+  };
+
+} // end namespace AMDiS
diff --git a/src/amdis/linearalgebra/mtl/CMakeLists.txt b/src/amdis/linearalgebra/mtl/CMakeLists.txt
index 20fb45a1..8dc3bb8d 100644
--- a/src/amdis/linearalgebra/mtl/CMakeLists.txt
+++ b/src/amdis/linearalgebra/mtl/CMakeLists.txt
@@ -6,6 +6,7 @@ install(FILES
     ITL_Solver.hpp
     KrylovRunner.hpp
     Preconditioner.hpp
+    Traits.hpp
     UmfpackRunner.hpp
 DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/amdis/linearalgebra/mtl)
 
diff --git a/src/amdis/linearalgebra/mtl/ITL_Preconditioner.hpp b/src/amdis/linearalgebra/mtl/ITL_Preconditioner.hpp
index a24349ef..1501c7b0 100644
--- a/src/amdis/linearalgebra/mtl/ITL_Preconditioner.hpp
+++ b/src/amdis/linearalgebra/mtl/ITL_Preconditioner.hpp
@@ -7,9 +7,9 @@
 #include <boost/numeric/mtl/vector/assigner.hpp>
 
 #include <amdis/linearalgebra/mtl/itl/masslumping.hpp>
-
-#include <amdis/CreatorMap.hpp>
 #include <amdis/linearalgebra/mtl/Preconditioner.hpp>
+#include <amdis/linearalgebra/mtl/Traits.hpp>
+#include <amdis/CreatorMap.hpp>
 
 namespace AMDiS
 {
@@ -73,17 +73,15 @@ namespace AMDiS
   template <class Matrix>
   using ICPreconditioner = itl::pc::ic_0<Matrix>;
 
-
-
-  template <class T, class Param, class Vector>
-  class DefaultCreators<PreconditionerInterface<mtl::compressed2D<T, Param>, Vector>>
+  template <class Traits>
+  class DefaultCreators< PreconditionerInterface<Traits> >
   {
-    using Matrix = mtl::compressed2D<T, Param>;
-    using PreconBase = PreconditionerInterface<Matrix, Vector>;
+    using Matrix = typename Traits::Mat;
+    using PreconBase = PreconditionerInterface<Traits>;
 
     template <template<class> class ITLPrecon>
     using PreconCreator
-      = typename Preconditioner<Matrix, Vector, ITLPrecon<Matrix>>::Creator;
+      = typename Preconditioner<Traits, ITLPrecon<Matrix>>::Creator;
 
     using Map = CreatorMap<PreconBase>;
 
@@ -113,17 +111,16 @@ namespace AMDiS
     }
   };
 
-
-  template <class Matrix, class Vector>
-  itl::pc::solver<PreconditionerInterface<Matrix, Vector>, Vector, false>
-  solve(PreconditionerInterface<Matrix, Vector> const& P, Vector const& vin)
+  template <class Traits>
+  itl::pc::solver<PreconditionerInterface<Traits>, typename Traits::Sol, false>
+  solve(PreconditionerInterface<Traits> const& P, typename Traits::Sol const& vin)
   {
     return {P, vin};
   }
 
-  template <class Matrix, class Vector>
-  itl::pc::solver<PreconditionerInterface<Matrix, Vector>, Vector, true>
-  adjoint_solve(PreconditionerInterface<Matrix, Vector> const& P, Vector const& vin)
+  template <class Traits>
+  itl::pc::solver<PreconditionerInterface<Traits>, typename Traits::Sol, true>
+  adjoint_solve(PreconditionerInterface<Traits> const& P, typename Traits::Sol const& vin)
   {
     return {P, vin};
   }
diff --git a/src/amdis/linearalgebra/mtl/ITL_Solver.hpp b/src/amdis/linearalgebra/mtl/ITL_Solver.hpp
index 5f2946d2..fd800d0c 100644
--- a/src/amdis/linearalgebra/mtl/ITL_Solver.hpp
+++ b/src/amdis/linearalgebra/mtl/ITL_Solver.hpp
@@ -18,6 +18,7 @@
 #include <amdis/Initfile.hpp>
 #include <amdis/linearalgebra/LinearSolver.hpp>
 #include <amdis/linearalgebra/mtl/KrylovRunner.hpp>
+#include <amdis/linearalgebra/mtl/Traits.hpp>
 #include <amdis/linearalgebra/mtl/UmfpackRunner.hpp>
 
 namespace AMDiS
@@ -366,7 +367,6 @@ namespace AMDiS
 
   // ===========================================================================
 
-
   /// Adds default creators for linear solvers based on `mtl::compressed2D`.
   /**
    * Adds creators for full-matrix aware solvers.
@@ -386,21 +386,21 @@ namespace AMDiS
    * - *preonly*: Just a pply a preconditioner, \see preonly_type
    * - *umfpack*: external UMFPACK solver, \see UmfpackRunner
    **/
-  template <class T, class Param, class Vector>
-  class DefaultCreators<LinearSolverInterface<mtl::compressed2D<T, Param>, Vector, Vector>>
+  template <class Traits>
+  class DefaultCreators< LinearSolverInterface<Traits> >
   {
-    using Matrix = mtl::compressed2D<T, Param>;
-    using SolverBase = LinearSolverInterface<Matrix, Vector, Vector>;
+    using Matrix = typename Traits::Mat;
+    using SolverBase = LinearSolverInterface<Traits>;
 
     template <class ITLSolver>
     using SolverCreator
-      = typename LinearSolver<Matrix, Vector, Vector,
-          KrylovRunner<ITLSolver, Matrix, Vector>>::Creator;
+      = typename LinearSolver<Traits,
+          KrylovRunner<ITLSolver,Traits>>::Creator;
 
 #ifdef HAVE_UMFPACK
     using UmfpackSolverCreator
-      = typename LinearSolver<Matrix, Vector, Vector,
-          UmfpackRunner<Matrix, Vector>>::Creator;
+      = typename LinearSolver<Traits,
+          UmfpackRunner<Traits>>::Creator;
 #endif
 
     using Map = CreatorMap<SolverBase>;
diff --git a/src/amdis/linearalgebra/mtl/KrylovRunner.hpp b/src/amdis/linearalgebra/mtl/KrylovRunner.hpp
index 2e5c62c1..bb46c181 100644
--- a/src/amdis/linearalgebra/mtl/KrylovRunner.hpp
+++ b/src/amdis/linearalgebra/mtl/KrylovRunner.hpp
@@ -7,7 +7,6 @@
 #include <boost/numeric/mtl/mtl.hpp>
 
 // AMDiS headers
-#include <amdis/linearalgebra/PreconditionerInterface.hpp>
 #include <amdis/linearalgebra/RunnerInterface.hpp>
 #include <amdis/linearalgebra/SolverInfo.hpp>
 
@@ -21,11 +20,14 @@ namespace AMDiS
    * Wrapper class for different MTL4 itl-solvers. These solvers
    * are parametrized by Matrix and Vector.
    **/
-  template <class ITLSolver, class Matrix, class Vector>
+  template <class ITLSolver, class Traits>
   class KrylovRunner
-      : public RunnerInterface<Matrix, Vector>
+      : public RunnerInterface<Traits>
   {
-    using Super = RunnerInterface<Matrix, Vector>;
+    using Super = RunnerInterface<Traits>;
+    using Matrix = typename Traits::Mat;
+    using Vector = typename Traits::Sol;
+    using Comm = typename Traits::Comm;
     using PreconBase = typename Super::PreconBase;
 
   public:
@@ -64,8 +66,9 @@ namespace AMDiS
     }
 
     /// Implementation of \ref RunnerInterface::init()
-    void init(Matrix const& A) override
+    void init(Matrix const& A, Comm& comm) override
     {
+      DUNE_UNUSED_PARAMETER(comm);
       L_->init(A);
       R_->init(A);
     }
@@ -78,8 +81,7 @@ namespace AMDiS
     }
 
     /// Implementation of \ref RunnerInterface::solve()
-    int solve(Matrix const& A, Vector& x, Vector const& b,
-              SolverInfo& solverInfo) override
+    int solve(Matrix const& A, Vector& x, Vector const& b, SolverInfo& solverInfo) override
     {
       test_exit(bool(L_), "There is no left preconditioner");
       test_exit(bool(R_), "There is no right preconditioner");
diff --git a/src/amdis/linearalgebra/mtl/Preconditioner.hpp b/src/amdis/linearalgebra/mtl/Preconditioner.hpp
index f4e1ee2e..70aad99b 100644
--- a/src/amdis/linearalgebra/mtl/Preconditioner.hpp
+++ b/src/amdis/linearalgebra/mtl/Preconditioner.hpp
@@ -9,12 +9,14 @@ namespace AMDiS
    *
    * \brief Wrapper for using ITL preconditioners in AMDiS.
    */
-  template <class Matrix, class Vector, class PreconRunner>
+  template <class Traits, class PreconRunner>
   class Preconditioner
-      : public PreconditionerInterface<Matrix, Vector>
+      : public PreconditionerInterface<Traits>
   {
     using Self = Preconditioner;
-    using Super = PreconditionerInterface<Matrix, Vector>;
+    using Matrix = typename Traits::Mat;
+    using Vector = typename Traits::Sol;
+    using Super = PreconditionerInterface<Traits>;
 
   public:
     /// A creator to be used instead of the constructor.
diff --git a/src/amdis/linearalgebra/mtl/Traits.hpp b/src/amdis/linearalgebra/mtl/Traits.hpp
new file mode 100644
index 00000000..87dc3899
--- /dev/null
+++ b/src/amdis/linearalgebra/mtl/Traits.hpp
@@ -0,0 +1,15 @@
+#pragma once
+
+#include <amdis/linearalgebra/Common.hpp>
+
+namespace AMDiS
+{
+  /** Traits class for a linear solver for the system AX=B using an FE space described by a dune-functions Basis
+   *  Contains typedefs specific to the MTL backend.
+   */
+  template <class A, class X, class B, class Basis>
+  class SolverTraits
+      : public SolverTraitsBase<A,X,B,Basis>
+  {};
+
+} // end namespace AMDiS
diff --git a/src/amdis/linearalgebra/mtl/UmfpackRunner.hpp b/src/amdis/linearalgebra/mtl/UmfpackRunner.hpp
index 01a45ef9..0f5729a6 100644
--- a/src/amdis/linearalgebra/mtl/UmfpackRunner.hpp
+++ b/src/amdis/linearalgebra/mtl/UmfpackRunner.hpp
@@ -8,9 +8,10 @@
 #include <boost/numeric/mtl/operation/two_norm.hpp>
 #include <boost/numeric/mtl/interface/umfpack_solve.hpp>
 
-#include <amdis/Output.hpp>
+#include <amdis/linearalgebra/mtl/Traits.hpp>
 #include <amdis/linearalgebra/RunnerInterface.hpp>
 #include <amdis/linearalgebra/SolverInfo.hpp>
+#include <amdis/Output.hpp>
 
 namespace AMDiS
 {
@@ -23,15 +24,14 @@ namespace AMDiS
   *
   * This is a direct solver for large sparse matrices.
   */
-  template <class Matrix, class Vector>
-  class UmfpackRunner;
-
-  template <class T, class Param, class Vector>
-  class UmfpackRunner<mtl::compressed2D<T, Param>, Vector>
-      : public RunnerInterface<mtl::compressed2D<T, Param>, Vector, Vector>
+  template <class Traits>
+  class UmfpackRunner
+      : public RunnerInterface<Traits>
   {
-    using Matrix = mtl::compressed2D<T, Param>;
-    using Super = RunnerInterface<Matrix, Vector>;
+    using Matrix = typename Traits::Mat;
+    using Vector = typename Traits::Sol;
+    using Comm = typename Traits::Comm;
+    using Super = RunnerInterface<Traits>;
     using PreconBase = typename Super::PreconBase;
 
     using SolverType = mtl::mat::umfpack::solver<Matrix>;
@@ -46,8 +46,9 @@ namespace AMDiS
     }
 
     /// Implementation of \ref RunnerInterface::init()
-    void init(Matrix const& matrix) override
+    void init(Matrix const& matrix, Comm&) override
     {
+      DUNE_UNUSED_PARAMETER(comm);
       try {
         solver_.reset(new SolverType(matrix, symmetricStrategy_, allocInit_));
       } catch (mtl::mat::umfpack::error const& e) {
@@ -59,10 +60,8 @@ namespace AMDiS
     void exit() override {}
 
     /// Implementation of \ref RunnerBase::solve()
-    int solve(Matrix const& A, Vector& x, Vector const& b,
-              SolverInfo& solverInfo) override
+    int solve(Matrix const& A, Vector& x, Vector const& b, SolverInfo& solverInfo) override
     {
-      AMDIS_FUNCNAME("Umfpack_Runner::solve()");
       test_exit(bool(solver_), "The umfpack solver was not initialized\n");
 
       int code = 0;
@@ -89,6 +88,7 @@ namespace AMDiS
     int symmetricStrategy_ = 0;
     double allocInit_ = 0.7;
   };
-}
+
+} // end namespace AMDiS
 
 #endif // HAVE_UMFPACK
diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt
index 57a2d1cf..ef3cfe35 100644
--- a/test/CMakeLists.txt
+++ b/test/CMakeLists.txt
@@ -58,6 +58,12 @@ dune_add_test(SOURCES GradientTest.cpp
 dune_add_test(SOURCES HybridSizeTest.cpp
   LINK_LIBRARIES amdis)
 
+dune_add_test(SOURCES ISTLCommTest.cpp
+  LINK_LIBRARIES amdis
+  MPI_RANKS 2 4
+  TIMEOUT 300
+  CMAKE_GUARD "MPI_FOUND AND dune-istl_FOUND")
+
 dune_add_test(SOURCES IntegrateTest.cpp
   LINK_LIBRARIES amdis
   CMD_ARGS "${CMAKE_SOURCE_DIR}/examples/init/ellipt.dat.2d")
diff --git a/test/ISTLCommTest.cpp b/test/ISTLCommTest.cpp
new file mode 100644
index 00000000..e3604680
--- /dev/null
+++ b/test/ISTLCommTest.cpp
@@ -0,0 +1,92 @@
+#include "config.h"
+
+#include <array>
+#include <bitset>
+#include <cmath>
+#include <string>
+#include <vector>
+
+#include <dune/common/fvector.hh>
+
+#include <dune/functions/functionspacebases/interpolate.hh>
+
+#include <dune/grid/yaspgrid.hh>
+
+#include <amdis/linearalgebra/istl/Communication.hpp>
+#include <amdis/Environment.hpp>
+#include <amdis/ProblemStatTraits.hpp>
+
+#include "Tests.hpp"
+
+using namespace AMDiS;
+
+template <class Basis>
+bool test(Basis& basis, std::string const& prefix)
+{
+  using Comm = ISTLCommunication<Basis>;
+  using GV = typename Basis::GridView;
+  using Grid = typename GV::Grid;
+  using Coord = typename Grid::template Codim<0>::Geometry::GlobalCoordinate;
+  using T = double;
+  static constexpr int d = Grid::dimension;
+
+  bool passed = true;
+
+  // Interpolate test function f onto dofs and reference
+  auto f = [&](const Coord& x) -> T { return std::pow(x[0],3) + x[1] + (d == 3 ? x[2] : 0.0); };
+  std::vector<T> ref(basis.size());
+  Dune::Functions::interpolate(basis, ref, f);
+  std::vector<T> dofs = ref;
+
+  // Make communicator and exchange dofs
+  auto comm = Comm::create(basis, prefix);
+  comm->copyOwnerToAll(dofs, dofs);
+
+  // Compare post-exchange data with reference
+  for (std::size_t i = 0; i < dofs.size(); ++i)
+    if (std::abs(dofs[i]-ref[i]) > AMDIS_TEST_TOL)
+      passed = false;
+
+  return passed;
+}
+
+int main(int argc, char** argv)
+{
+  using namespace Dune::Functions::BasisFactory;
+
+  Environment env(argc, argv);
+
+  if (Environment::mpiSize() == 1)
+    return 0;
+
+  using YaspGrid2d = Dune::YaspGrid< 2, Dune::EquidistantOffsetCoordinates<double, 2> >;
+  using YaspGrid3d = Dune::YaspGrid< 3, Dune::EquidistantOffsetCoordinates<double, 3> >;
+
+  // constants
+  using Coord2d = Dune::FieldVector<double, 2>;
+  using Coord3d = Dune::FieldVector<double, 3>;
+  Coord2d lower2d(1.0);
+  Coord2d upper2d(2.0);
+  std::array<int, 2> nElements2d{16,3};
+  Coord3d lower3d(1.0);
+  Coord3d upper3d(2.0);
+  std::array<int, 3> nElements3d{16,3,3};
+  int ovlp = 1;
+
+  {
+    auto grid = std::make_unique<YaspGrid2d>(lower2d, upper2d, nElements2d, std::bitset<2>(), ovlp);
+    auto l1 = LagrangeBasis<YaspGrid2d, 1>::create(grid->leafGridView());
+    AMDIS_TEST(test(l1, "Yasp2d_L1_Ovlp"));
+    auto th = TaylorHoodBasis<YaspGrid2d, 1>::create(grid->leafGridView());
+    AMDIS_TEST(test(th, "Yasp2d_TH_Ovlp"));
+  }
+  {
+    auto grid = std::make_unique<YaspGrid3d>(lower3d, upper3d, nElements3d, std::bitset<3>(), ovlp);
+    auto l1 = LagrangeBasis<YaspGrid3d, 1>::create(grid->leafGridView());
+    AMDIS_TEST(test(l1, "Yasp3d_L1_Ovlp"));
+    auto th = TaylorHoodBasis<YaspGrid3d, 1>::create(grid->leafGridView());
+    AMDIS_TEST(test(th, "Yasp3d_TH_Ovlp"));
+  }
+
+  return report_errors();
+}
-- 
GitLab