From 4253bc0541d01fe8e38360781dea967e47386737 Mon Sep 17 00:00:00 2001
From: kraus <christof.kraus@psi.ch>
Date: Tue, 18 Aug 2020 09:46:52 +0200
Subject: [PATCH] check the length of the elements and compare it with the
 length of a time step; check that the user inputs for DT and MAXSTEPS of the
 TRACK command and for L of the elements are positive values; replace the
 length_m member variables in the elements with method call getElementLength;

---
 src/Algorithms/IndexMap.cpp                   |  6 ++--
 src/Algorithms/IndexMap.h                     |  2 +-
 src/Algorithms/OrbitThreader.cpp              | 31 +++++++++++++++++--
 src/Algorithms/OrbitThreader.h                | 10 ++++--
 src/Algorithms/ParallelTTracker.cpp           |  2 +-
 src/Classic/AbsBeamline/Bend2D.cpp            |  4 +--
 src/Classic/AbsBeamline/BendBase.cpp          |  2 --
 src/Classic/AbsBeamline/BendBase.h            | 14 ---------
 src/Classic/AbsBeamline/Drift.h               |  9 +++++-
 src/Classic/AbsBeamline/ElementBase.h         |  8 +++++
 src/Classic/AbsBeamline/Marker.h              | 10 +++++-
 src/Classic/AbsBeamline/Monitor.h             |  8 +++++
 src/Classic/AbsBeamline/RBend.cpp             |  4 +--
 src/Classic/AbsBeamline/RBend3D.cpp           |  8 ++---
 src/Classic/AbsBeamline/RFCavity.cpp          | 10 +++---
 src/Classic/AbsBeamline/RFCavity.h            |  5 ++-
 src/Classic/AbsBeamline/SBend.cpp             |  5 ++-
 src/Classic/AbsBeamline/Solenoid.cpp          | 19 ++++--------
 src/Classic/AbsBeamline/Solenoid.h            |  7 ++---
 src/Classic/AbsBeamline/Source.h              |  8 +++++
 src/Classic/AbsBeamline/Stripper.h            | 10 +++++-
 src/Classic/AbsBeamline/TravelingWave.cpp     | 16 ++++------
 src/Classic/AbsBeamline/TravelingWave.h       |  3 +-
 .../BeamlineGeometry/Euclid3DGeometry.cpp     |  7 ++++-
 .../BeamlineGeometry/PlanarArcGeometry.cpp    |  8 ++++-
 .../BeamlineGeometry/RBendGeometry.cpp        |  9 ++----
 src/Classic/BeamlineGeometry/RBendGeometry.h  |  7 +----
 .../BeamlineGeometry/StraightGeometry.cpp     | 14 +++++----
 .../BeamlineGeometry/VarRadiusGeometry.h      | 13 +++++---
 src/Elements/OpalRBend.cpp                    | 28 ++++++-----------
 src/Elements/OpalRBend3D.cpp                  |  4 +--
 src/Elements/OpalSBend.cpp                    |  5 ---
 src/Track/TrackCmd.cpp                        | 31 ++++++++++++-------
 33 files changed, 185 insertions(+), 142 deletions(-)

diff --git a/src/Algorithms/IndexMap.cpp b/src/Algorithms/IndexMap.cpp
index b6a97d256..62bc71413 100644
--- a/src/Algorithms/IndexMap.cpp
+++ b/src/Algorithms/IndexMap.cpp
@@ -393,9 +393,9 @@ std::pair<double, double> IndexMap::getRange(const IndexMap::value_t::value_type
     return range;
 }
 
-IndexMap::value_t IndexMap::getTouchingElements(const std::pair<double, double> &range) {
-    map_t::iterator it = mapRange2Element_m.begin();
-    const map_t::iterator end = mapRange2Element_m.end();
+IndexMap::value_t IndexMap::getTouchingElements(const std::pair<double, double> &range) const {
+    map_t::const_iterator it = mapRange2Element_m.begin();
+    const map_t::const_iterator end = mapRange2Element_m.end();
     IndexMap::value_t touchingElements;
 
     for (; it != end; ++ it) {
diff --git a/src/Algorithms/IndexMap.h b/src/Algorithms/IndexMap.h
index f2a3ee9ef..8a6d0d0b5 100644
--- a/src/Algorithms/IndexMap.h
+++ b/src/Algorithms/IndexMap.h
@@ -54,7 +54,7 @@ public:
     size_t numElements() const;
     std::pair<double, double> getRange(const IndexMap::value_t::value_type &element,
                                        double position) const;
-    IndexMap::value_t getTouchingElements(const std::pair<double, double> &range);
+    IndexMap::value_t getTouchingElements(const std::pair<double, double> &range) const;
 
     class OutOfBounds: public OpalException {
     public:
diff --git a/src/Algorithms/OrbitThreader.cpp b/src/Algorithms/OrbitThreader.cpp
index 893fedd44..805b78a89 100644
--- a/src/Algorithms/OrbitThreader.cpp
+++ b/src/Algorithms/OrbitThreader.cpp
@@ -53,14 +53,15 @@ OrbitThreader::OrbitThreader(const PartData &ref,
                              double maxDiffZBunch,
                              double t,
                              double dt,
-                             double zstop,
+                             StepSizeConfig stepSizes,
                              OpalBeamline &bl) :
     r_m(r),
     p_m(p),
     pathLength_m(s),
     time_m(t),
     dt_m(dt),
-    zstop_m(zstop),
+    stepSizes_m(stepSizes),
+    zstop_m(stepSizes.getFinalZStop() + std::copysign(1.0, dt) * 2 * maxDiffZBunch),
     itsOpalBeamline_m(bl),
     errorFlag_m(0),
     integrator_m(ref),
@@ -105,6 +106,29 @@ OrbitThreader::OrbitThreader(const PartData &ref,
     computeBoundingBox();
 }
 
+void OrbitThreader::checkElementLengths(const std::set<std::shared_ptr<Component>>& fields) {
+    while (!stepSizes_m.reachedEnd() && pathLength_m > stepSizes_m.getZStop()) {
+        ++ stepSizes_m;
+    }
+    if (stepSizes_m.reachedEnd()) {
+        return;
+    }
+    double driftLength = Physics::c * std::abs(stepSizes_m.getdT()) * euclidean_norm(p_m) / Util::getGamma(p_m);
+    for (const std::shared_ptr<Component> field : fields) {
+        double length = field->getElementLength();
+        int numSteps = field->getRequiredNumberOfTimeSteps();
+
+        if (length < numSteps * driftLength) {
+            throw OpalException("OrbitThreader::checkElementLengths",
+                                "The time step is too long compared to the length of the\n"
+                                "element '" + field->getName() + "'\n" +
+                                "The length of the element is: " + std::to_string(length) + "\n"
+                                "The distance the particles drift in " + std::to_string(numSteps) +
+                                " time step(s) is: " + std::to_string(numSteps * driftLength));
+        }
+    }
+}
+
 void OrbitThreader::execute() {
     double initialPathLength = pathLength_m;
 
@@ -123,6 +147,7 @@ void OrbitThreader::execute() {
     auto elementSet = itsOpalBeamline_m.getElements(nextR);
     errorFlag_m = EVERYTHINGFINE;
     do {
+        checkElementLengths(elementSet);
         if (containsCavity(elementSet)) {
             autophaseCavities(elementSet, visitedElements);
         }
@@ -447,4 +472,4 @@ double OrbitThreader::computeDriftLengthToBoundingBox(const std::set<std::shared
     }
 
     return std::numeric_limits<double>::max();
-}
\ No newline at end of file
+}
diff --git a/src/Algorithms/OrbitThreader.h b/src/Algorithms/OrbitThreader.h
index 37d985042..c9b307792 100644
--- a/src/Algorithms/OrbitThreader.h
+++ b/src/Algorithms/OrbitThreader.h
@@ -23,6 +23,7 @@
 #define OPAL_ORBITTHREADER_H
 
 #include "Algorithms/IndexMap.h"
+#include "Algorithms/StepSizeConfig.h"
 #include "Algorithms/Vektor.h"
 #include "Elements/OpalBeamline.h"
 #include "Steppers/BorisPusher.h"
@@ -41,7 +42,7 @@ public:
                   double maxDiffZBunch,
                   double t,
                   double dT,
-                  double zstop,
+                  StepSizeConfig stepSizes,
                   OpalBeamline &bl);
 
     void execute();
@@ -51,7 +52,7 @@ public:
 
     std::pair<double, double> getRange(const IndexMap::value_t::value_type &element,
                                        double position) const;
-    IndexMap::value_t getTouchingElements(const std::pair<double, double> &range);
+    IndexMap::value_t getTouchingElements(const std::pair<double, double> &range) const;
 
 private:
     /// position of reference particle in lab coordinates
@@ -69,6 +70,7 @@ private:
     double dt_m;
 
     /// final position in path length
+    StepSizeConfig stepSizes_m;
     const double zstop_m;
 
     OpalBeamline &itsOpalBeamline_m;
@@ -112,6 +114,8 @@ private:
     double computeDriftLengthToBoundingBox(const std::set<std::shared_ptr<Component>> & elements,
                                            const Vector_t & position,
                                            const Vector_t & direction) const;
+
+    void checkElementLengths(const std::set<std::shared_ptr<Component>>& elements);
 };
 
 inline
@@ -127,7 +131,7 @@ std::pair<double, double> OrbitThreader::getRange(const IndexMap::value_t::value
 }
 
 inline
-IndexMap::value_t OrbitThreader::getTouchingElements(const std::pair<double, double> &range) {
+IndexMap::value_t OrbitThreader::getTouchingElements(const std::pair<double, double> &range) const {
     return imap_m.getTouchingElements(range);
 }
 
diff --git a/src/Algorithms/ParallelTTracker.cpp b/src/Algorithms/ParallelTTracker.cpp
index b06468b77..f45617b7e 100644
--- a/src/Algorithms/ParallelTTracker.cpp
+++ b/src/Algorithms/ParallelTTracker.cpp
@@ -247,7 +247,7 @@ void ParallelTTracker::execute() {
                       -rmin(2),
                       itsBunch_m->getT(),
                       (back_track? -minTimeStep: minTimeStep),
-                      stepSizes_m.getFinalZStop() + (back_track? -1: 1) * 2 * rmax(2),
+                      stepSizes_m,
                       itsOpalBeamline_m);
 
     oth.execute();
diff --git a/src/Classic/AbsBeamline/Bend2D.cpp b/src/Classic/AbsBeamline/Bend2D.cpp
index 604b0c462..ba0aace86 100644
--- a/src/Classic/AbsBeamline/Bend2D.cpp
+++ b/src/Classic/AbsBeamline/Bend2D.cpp
@@ -208,7 +208,7 @@ void Bend2D::initialise(PartBunchBase<double, 3> *bunch,
         double bendAngleY = 0.0;
         calculateRefTrajectory(bendAngleX, bendAngleY);
         print(msg, bendAngleX, bendAngleY);
-
+        setElementLength(endField_m - startField_m);
         // Pass start and end of field to calling function.
         startField = startField_m;
         endField = endField_m;
@@ -1217,7 +1217,7 @@ bool Bend2D::setupBendGeometry(double &startField, double &endField) {
 
 bool Bend2D::setupDefaultFieldMap() {
 
-    if (length_m <= 0.0) {
+    if (getElementLength() <= 0.0) {
         ERRORMSG("If using \"1DPROFILE1-DEFAULT\" field map you must set the "
                  "chord length of the bend using the L attribute in the OPAL "
                  "input file."
diff --git a/src/Classic/AbsBeamline/BendBase.cpp b/src/Classic/AbsBeamline/BendBase.cpp
index 05b59913a..827cdf873 100644
--- a/src/Classic/AbsBeamline/BendBase.cpp
+++ b/src/Classic/AbsBeamline/BendBase.cpp
@@ -10,7 +10,6 @@ BendBase::BendBase():
 
 BendBase::BendBase(const BendBase &right):
     Component(right),
-    length_m(right.length_m),
     chordLength_m(right.chordLength_m),
     angle_m(right.angle_m),
     entranceAngle_m(right.entranceAngle_m),
@@ -27,7 +26,6 @@ BendBase::BendBase(const BendBase &right):
 
 BendBase::BendBase(const std::string &name):
     Component(name),
-    length_m(0.0),
     chordLength_m(0.0),
     angle_m(0.0),
     entranceAngle_m(0.0),
diff --git a/src/Classic/AbsBeamline/BendBase.h b/src/Classic/AbsBeamline/BendBase.h
index a2bfeb41d..9e5d8d0a9 100644
--- a/src/Classic/AbsBeamline/BendBase.h
+++ b/src/Classic/AbsBeamline/BendBase.h
@@ -17,8 +17,6 @@ public:
     /// Indicates that element bends the beam.
     virtual bool bends() const;
 
-    void setLength(double length);
-    double getLength() const;
     double getChordLength() const;
     virtual void setBendAngle(double angle);
     double getBendAngle() const;
@@ -51,7 +49,6 @@ protected:
     /// Calculate beta*gamma from design energy
     double calcBetaGamma() const;
 
-    double length_m;
     double chordLength_m;
     double angle_m;         ///< Bend angle
     double entranceAngle_m; ///< Angle between incoming reference trajectory
@@ -81,17 +78,6 @@ bool BendBase::bends() const {
     return true;
 }
 
-inline
-void BendBase::setLength(double length) {
-    length_m = std::abs(length);
-}
-
-inline
-double BendBase::getLength() const
-{
-    return length_m;
-}
-
 inline
 double BendBase::getChordLength() const {
     return chordLength_m;
diff --git a/src/Classic/AbsBeamline/Drift.h b/src/Classic/AbsBeamline/Drift.h
index 4a2a869e3..c2a6d7580 100644
--- a/src/Classic/AbsBeamline/Drift.h
+++ b/src/Classic/AbsBeamline/Drift.h
@@ -60,6 +60,7 @@ public:
     //set number of slices for map tracking
     std::size_t getNSlices() const; // Philippe was here
 
+    virtual int getRequiredNumberOfTimeSteps() const override;
 private:
 
     double startField_m;
@@ -69,4 +70,10 @@ private:
     void operator=(const Drift &);
 };
 
-#endif // CLASSIC_Drift_HH
+inline
+int Drift::getRequiredNumberOfTimeSteps() const
+{
+    return 1;
+}
+
+#endif // CLASSIC_Drift_HH
\ No newline at end of file
diff --git a/src/Classic/AbsBeamline/ElementBase.h b/src/Classic/AbsBeamline/ElementBase.h
index 4c813e16c..7121877da 100644
--- a/src/Classic/AbsBeamline/ElementBase.h
+++ b/src/Classic/AbsBeamline/ElementBase.h
@@ -372,6 +372,8 @@ public:
 
     virtual BoundingBox getBoundingBoxInLabCoords() const;
 
+    virtual int getRequiredNumberOfTimeSteps() const;
+
 protected:
     bool isInsideTransverse(const Vector_t &r) const;
 
@@ -613,4 +615,10 @@ inline
 bool ElementBase::isElementPositionSet() const
 { return elemedgeSet_m; }
 
+inline
+int ElementBase::getRequiredNumberOfTimeSteps() const
+{
+    return 10;
+}
+
 #endif // CLASSIC_ElementBase_HH
\ No newline at end of file
diff --git a/src/Classic/AbsBeamline/Marker.h b/src/Classic/AbsBeamline/Marker.h
index a0ab5d089..f33abe6a0 100644
--- a/src/Classic/AbsBeamline/Marker.h
+++ b/src/Classic/AbsBeamline/Marker.h
@@ -53,10 +53,18 @@ public:
 
     virtual void getDimensions(double &zBegin, double &zEnd) const override;
 
+    virtual int getRequiredNumberOfTimeSteps() const override;
+
 private:
 
     // Not implemented.
     void operator=(const Marker &);
 };
 
-#endif // CLASSIC_Marker_HH
+inline
+int Marker::getRequiredNumberOfTimeSteps() const
+{
+    return 1;
+}
+
+#endif // CLASSIC_Marker_HH
\ No newline at end of file
diff --git a/src/Classic/AbsBeamline/Monitor.h b/src/Classic/AbsBeamline/Monitor.h
index 16cffa89d..b44009703 100644
--- a/src/Classic/AbsBeamline/Monitor.h
+++ b/src/Classic/AbsBeamline/Monitor.h
@@ -105,6 +105,8 @@ public:
     void setType(Type type);
 
     static void writeStatistics();
+
+    virtual int getRequiredNumberOfTimeSteps() const override;
 private:
 
     // Not implemented.
@@ -125,4 +127,10 @@ void Monitor::setType(Monitor::Type type) {
     type_m = type;
 }
 
+inline
+int Monitor::getRequiredNumberOfTimeSteps() const
+{
+    return 1;
+}
+
 #endif // CLASSIC_Monitor_HH
\ No newline at end of file
diff --git a/src/Classic/AbsBeamline/RBend.cpp b/src/Classic/AbsBeamline/RBend.cpp
index 740d9cc8a..36f5f3e5c 100644
--- a/src/Classic/AbsBeamline/RBend.cpp
+++ b/src/Classic/AbsBeamline/RBend.cpp
@@ -135,14 +135,14 @@ bool RBend::findChordLength(double &chordLength) {
     const double angle = getBendAngle();
     if (std::abs(angle) > 0.0) {
         double E1 = std::copysign(1.0, angle) * getEntranceAngle();
-        chordLength = 2 * getLength() * std::sin(0.5 * std::abs(angle)) /
+        chordLength = 2 * getElementLength() * std::sin(0.5 * std::abs(angle)) /
             (std::sin(E1) + std::sin(std::abs(angle) - E1));
     } else {
         double refCharge = RefPartBunch_m->getQ();
         double amplitude = (fieldAmplitudeY_m != 0.0) ? fieldAmplitudeY_m : fieldAmplitudeX_m;
         double fieldAmplitude = std::copysign(1.0, refCharge) * std::abs(amplitude);
         double designRadius = calcDesignRadius(fieldAmplitude);
-        chordLength = std::sin(0.5 * (std::asin(getLength() / designRadius - std::sin(getEntranceAngle())) + getEntranceAngle())) * 2 * designRadius;
+        chordLength = std::sin(0.5 * (std::asin(getElementLength() / designRadius - std::sin(getEntranceAngle())) + getEntranceAngle())) * 2 * designRadius;
     }
 
     return true;
diff --git a/src/Classic/AbsBeamline/RBend3D.cpp b/src/Classic/AbsBeamline/RBend3D.cpp
index 9ef410715..247f68e2b 100644
--- a/src/Classic/AbsBeamline/RBend3D.cpp
+++ b/src/Classic/AbsBeamline/RBend3D.cpp
@@ -104,7 +104,7 @@ void RBend3D::initialise(PartBunchBase<double, 3> *bunch, double &startField, do
         double zBegin = 0.0, zEnd = 0.0;
         fieldmap_m->getFieldDimensions(zBegin, zEnd);
 
-        if (length_m == 0.0) {
+        if (getElementLength() == 0.0) {
             chordLength_m = 0.0;
             double fieldLength = zEnd - zBegin;
             double z = 0.0, dz = fieldLength / 1000;
@@ -121,9 +121,9 @@ void RBend3D::initialise(PartBunchBase<double, 3> *bunch, double &startField, do
                 z -= dz;
             }
             chordLength_m = z - zEntryEdge;
-            length_m = chordLength_m;
+            setElementLength(chordLength_m);
         } else {
-            chordLength_m = length_m;
+            chordLength_m = getElementLength();
         }
 
         startField_m = zBegin;
@@ -200,7 +200,7 @@ void RBend3D::goOffline() {
 
 void RBend3D::getDimensions(double &zBegin, double &zEnd) const {
     zBegin = startField_m;
-    zEnd = startField_m + length_m;
+    zEnd = startField_m + getElementLength();
 }
 
 
diff --git a/src/Classic/AbsBeamline/RFCavity.cpp b/src/Classic/AbsBeamline/RFCavity.cpp
index af30667df..b07b73f4a 100644
--- a/src/Classic/AbsBeamline/RFCavity.cpp
+++ b/src/Classic/AbsBeamline/RFCavity.cpp
@@ -61,7 +61,6 @@ RFCavity::RFCavity(const RFCavity &right):
     autophaseVeto_m(right.autophaseVeto_m),
     designEnergy_m(right.designEnergy_m),
     fieldmap_m(right.fieldmap_m),
-    length_m(right.length_m),
     startField_m(right.startField_m),
     endField_m(right.endField_m),
     type_m(right.type_m),
@@ -95,7 +94,6 @@ RFCavity::RFCavity(const std::string &name):
     autophaseVeto_m(false),
     designEnergy_m(-1.0),
     fieldmap_m(nullptr),
-    length_m(0.0),
     startField_m(0.0),
     endField_m(0.0),
     type_m(SW),
@@ -131,7 +129,7 @@ bool RFCavity::apply(const Vector_t &R,
                      Vector_t &E,
                      Vector_t &B) {
     if (R(2) >= startField_m &&
-        R(2) < startField_m + length_m) {
+        R(2) < startField_m + getElementLength()) {
         Vector_t tmpE(0.0, 0.0, 0.0), tmpB(0.0, 0.0, 0.0);
 
         bool outOfBounds = fieldmap_m->getFieldstrength(R, tmpE, tmpB);
@@ -151,7 +149,7 @@ bool RFCavity::applyToReferenceParticle(const Vector_t &R,
                                         Vector_t &B) {
 
     if (R(2) >= startField_m &&
-        R(2) < startField_m + length_m) {
+        R(2) < startField_m + getElementLength()) {
         Vector_t tmpE(0.0, 0.0, 0.0), tmpB(0.0, 0.0, 0.0);
 
         bool outOfBounds = fieldmap_m->getFieldstrength(R, tmpE, tmpB);
@@ -200,7 +198,7 @@ void RFCavity::initialise(PartBunchBase<double, 3> *bunch, double &startField, d
         }
         frequency_m = fieldmap_m->getFrequency();
     }
-    length_m = endField - startField_m;
+    setElementLength(endField - startField_m);
 }
 
 // In current version ,this function reads in the cavity voltage profile data from file.
@@ -674,7 +672,7 @@ std::pair<double, double> RFCavity::trackOnAxisParticle(const double &p0,
     BorisPusher integrator(*RefPartBunch_m->getReference());
     const double cdt = Physics::c * dt;
     const double zbegin = startField_m;
-    const double zend = length_m + startField_m;
+    const double zend = getElementLength() + startField_m;
 
     Vector_t z(0.0, 0.0, zbegin);
     double dz = 0.5 * p(2) / Util::getGamma(p) * cdt;
diff --git a/src/Classic/AbsBeamline/RFCavity.h b/src/Classic/AbsBeamline/RFCavity.h
index 64251e3b3..21f504558 100644
--- a/src/Classic/AbsBeamline/RFCavity.h
+++ b/src/Classic/AbsBeamline/RFCavity.h
@@ -226,7 +226,6 @@ protected:
     double designEnergy_m;
 
     Fieldmap* fieldmap_m;
-    double length_m;
     double startField_m;         /**< starting point of field(m)*/
 
 private:
@@ -510,9 +509,9 @@ CoordinateSystemTrafo RFCavity::getEdgeToBegin() const {
 
 inline
 CoordinateSystemTrafo RFCavity::getEdgeToEnd() const {
-    CoordinateSystemTrafo ret(Vector_t(0, 0, startField_m + length_m),
+    CoordinateSystemTrafo ret(Vector_t(0, 0, startField_m + getElementLength()),
                               Quaternion(1, 0, 0, 0));
     return ret;
 }
 
-#endif // CLASSIC_RFCavity_HH
+#endif // CLASSIC_RFCavity_HH
\ No newline at end of file
diff --git a/src/Classic/AbsBeamline/SBend.cpp b/src/Classic/AbsBeamline/SBend.cpp
index a62fb9a5c..6c89c6708 100644
--- a/src/Classic/AbsBeamline/SBend.cpp
+++ b/src/Classic/AbsBeamline/SBend.cpp
@@ -97,7 +97,6 @@ bool SBend::findChordLength(double &chordLength) {
      * Find bend chord length. If this was not set by the user using the
      * L (length) attribute, infer it from the field map.
      */
-    chordLength = getLength();
+    chordLength = getElementLength();
     return true;
-}
-
+}
\ No newline at end of file
diff --git a/src/Classic/AbsBeamline/Solenoid.cpp b/src/Classic/AbsBeamline/Solenoid.cpp
index 3c87f14f2..e5e2dae53 100644
--- a/src/Classic/AbsBeamline/Solenoid.cpp
+++ b/src/Classic/AbsBeamline/Solenoid.cpp
@@ -44,7 +44,6 @@ Solenoid::Solenoid(const Solenoid &right):
     scale_m(right.scale_m),
     scaleError_m(right.scaleError_m),
     startField_m(right.startField_m),
-    length_m(right.length_m),
     fast_m(right.fast_m) {
 }
 
@@ -56,7 +55,6 @@ Solenoid::Solenoid(const std::string &name):
     scale_m(1.0),
     scaleError_m(0.0),
     startField_m(0.0),
-    length_m(0.0),
     fast_m(true) {
 }
 
@@ -89,7 +87,7 @@ bool Solenoid::apply(const size_t &i, const double &t, Vector_t &E, Vector_t &B)
 
 bool Solenoid::apply(const Vector_t &R, const Vector_t &/*P*/, const  double &/*t*/, Vector_t &/*E*/, Vector_t &B) {
     if (R(2) >= startField_m
-        && R(2) < startField_m + length_m) {
+        && R(2) < startField_m + getElementLength()) {
         Vector_t tmpE(0.0, 0.0, 0.0), tmpB(0.0, 0.0, 0.0);
 
         const bool outOfBounds = myFieldmap_m->getFieldstrength(R, tmpE, tmpB);
@@ -104,7 +102,7 @@ bool Solenoid::apply(const Vector_t &R, const Vector_t &/*P*/, const  double &/*
 bool Solenoid::applyToReferenceParticle(const Vector_t &R, const Vector_t &/*P*/, const  double &/*t*/, Vector_t &/*E*/, Vector_t &B) {
 
     if (R(2) >= startField_m
-        && R(2) < startField_m + length_m) {
+        && R(2) < startField_m + getElementLength()) {
         Vector_t tmpE(0.0, 0.0, 0.0), tmpB(0.0, 0.0, 0.0);
 
         const bool outOfBounds = myFieldmap_m->getFieldstrength(R, tmpE, tmpB);
@@ -131,8 +129,8 @@ void Solenoid::initialise(PartBunchBase<double, 3> *bunch, double &startField, d
         myFieldmap_m->getFieldDimensions(zBegin, zEnd);
 
         startField_m = zBegin;
-        length_m = zEnd - zBegin;
-        endField = startField + length_m;
+        setElementLength(zEnd - zBegin);
+        endField = startField + getElementLength();
     } else {
         endField = startField;
     }
@@ -166,7 +164,7 @@ void Solenoid::setDKS(double ks) {
 
 void Solenoid::getDimensions(double &zBegin, double &zEnd) const {
     zBegin = startField_m;
-    zEnd = startField_m + length_m;
+    zEnd = startField_m + getElementLength();
 }
 
 
@@ -179,13 +177,8 @@ bool Solenoid::isInside(const Vector_t &r) const {
         && myFieldmap_m->isInside(r);
 }
 
-
-double Solenoid::getElementLength() const {
-    return length_m;
-}
-
 void Solenoid::getElementDimensions(double &begin,
                                          double &end) const {
     begin = startField_m;
-    end = begin + length_m;
+    end = begin + getElementLength();
 }
\ No newline at end of file
diff --git a/src/Classic/AbsBeamline/Solenoid.h b/src/Classic/AbsBeamline/Solenoid.h
index 550889e61..d6826b0d7 100644
--- a/src/Classic/AbsBeamline/Solenoid.h
+++ b/src/Classic/AbsBeamline/Solenoid.h
@@ -82,8 +82,6 @@ public:
 
     virtual bool isInside(const Vector_t &r) const override;
 
-    virtual double getElementLength() const override;
-
     virtual void getElementDimensions(double &zBegin, double &zEnd) const override;
 
     virtual CoordinateSystemTrafo getEdgeToBegin() const override;
@@ -98,7 +96,6 @@ private:
     double scaleError_m;                /**< scale multiplier error*/
 
     double startField_m;           /**< startingpoint of field, m*/
-    double length_m;
 
     bool fast_m;
     // Not implemented.
@@ -119,9 +116,9 @@ CoordinateSystemTrafo Solenoid::getEdgeToBegin() const
 inline
 CoordinateSystemTrafo Solenoid::getEdgeToEnd() const
 {
-    CoordinateSystemTrafo ret(Vector_t(0, 0, startField_m + length_m),
+    CoordinateSystemTrafo ret(Vector_t(0, 0, startField_m + getElementLength()),
                               Quaternion(1, 0, 0, 0));
 
     return ret;
 }
-#endif // CLASSIC_Solenoid_HH
+#endif // CLASSIC_Solenoid_HH
\ No newline at end of file
diff --git a/src/Classic/AbsBeamline/Source.h b/src/Classic/AbsBeamline/Source.h
index 1e4fa1f30..4453a9476 100644
--- a/src/Classic/AbsBeamline/Source.h
+++ b/src/Classic/AbsBeamline/Source.h
@@ -39,6 +39,8 @@ public:
 
     virtual void getDimensions(double &zBegin, double &zEnd) const override;
 
+    virtual int getRequiredNumberOfTimeSteps() const override;
+
     void setTransparent();
 private:
 
@@ -52,4 +54,10 @@ private:
     // Not implemented.
     void operator=(const Source &);
 };
+
+inline
+int Source::getRequiredNumberOfTimeSteps() const
+{
+    return 0;
+}
 #endif // CLASSIC_SOURCE_HH
\ No newline at end of file
diff --git a/src/Classic/AbsBeamline/Stripper.h b/src/Classic/AbsBeamline/Stripper.h
index fa1d186a6..6193e3998 100644
--- a/src/Classic/AbsBeamline/Stripper.h
+++ b/src/Classic/AbsBeamline/Stripper.h
@@ -56,6 +56,8 @@ public:
     bool   getStop() const;
     ///@}
 
+    virtual int getRequiredNumberOfTimeSteps() const override;
+
 private:
     /// Record hits when bunch particles pass
     virtual bool doCheck(PartBunchBase<double, 3> *bunch, const int turnnumber, const double t, const double tstep) override;
@@ -72,4 +74,10 @@ private:
     bool   stop_m;     ///< Flag if particles should be stripped or stopped
 };
 
-#endif // CLASSIC_Stripper_HH
+inline
+int Stripper::getRequiredNumberOfTimeSteps() const
+{
+    return 1;
+}
+
+#endif // CLASSIC_Stripper_HH
\ No newline at end of file
diff --git a/src/Classic/AbsBeamline/TravelingWave.cpp b/src/Classic/AbsBeamline/TravelingWave.cpp
index 412c1c1a6..50e2f4e38 100644
--- a/src/Classic/AbsBeamline/TravelingWave.cpp
+++ b/src/Classic/AbsBeamline/TravelingWave.cpp
@@ -87,7 +87,7 @@ bool TravelingWave::apply(const size_t &i, const double &t, Vector_t &E, Vector_
 }
 
 bool TravelingWave::apply(const Vector_t &R, const Vector_t &/*P*/, const double &t, Vector_t &E, Vector_t &B) {
-    if (R(2) < -0.5 * PeriodLength_m || R(2) + 0.5 * PeriodLength_m >= length_m) return false;
+    if (R(2) < -0.5 * PeriodLength_m || R(2) + 0.5 * PeriodLength_m >= getElementLength()) return false;
 
     Vector_t tmpR = Vector_t(R(0), R(1), R(2) + 0.5 * PeriodLength_m);
     double tmpcos, tmpsin;
@@ -140,7 +140,7 @@ bool TravelingWave::apply(const Vector_t &R, const Vector_t &/*P*/, const double
 
 bool TravelingWave::applyToReferenceParticle(const Vector_t &R, const Vector_t &/*P*/, const double &t, Vector_t &E, Vector_t &B) {
 
-    if (R(2) < -0.5 * PeriodLength_m || R(2) + 0.5 * PeriodLength_m >= length_m) return false;
+    if (R(2) < -0.5 * PeriodLength_m || R(2) + 0.5 * PeriodLength_m >= getElementLength()) return false;
 
     Vector_t tmpR = Vector_t(R(0), R(1), R(2) + 0.5 * PeriodLength_m);
     double tmpcos, tmpsin;
@@ -209,7 +209,7 @@ void TravelingWave::initialise(PartBunchBase<double, 3> *bunch, double &startFie
                                       "The field map of a traveling wave structure has to begin at 0.0");
     }
 
-    PeriodLength_m = length_m / 2.0;
+    PeriodLength_m = (zEnd - zBegin) / 2.0;
     CellLength_m = PeriodLength_m * Mode_m;
     startField_m = -0.5 * PeriodLength_m;
 
@@ -219,7 +219,7 @@ void TravelingWave::initialise(PartBunchBase<double, 3> *bunch, double &startFie
 
     startField = -PeriodLength_m / 2.0;
     endField = startField + startExitField_m + PeriodLength_m / 2.0;
-    length_m = endField - startField;
+    setElementLength(endField - startField);
 
     scaleCore_m = scale_m / std::sin(Physics::two_pi * Mode_m);
     scaleCoreError_m = scaleError_m / std::sin(Physics::two_pi * Mode_m);
@@ -247,18 +247,14 @@ void TravelingWave::goOffline() {
 
 void TravelingWave::getDimensions(double &zBegin, double &zEnd) const {
     zBegin = -0.5 * PeriodLength_m;
-    zEnd = zBegin + length_m;
+    zEnd = zBegin + getElementLength();
 }
 
 
-double TravelingWave::getElementLength() const {
-    return length_m;
-}
-
 void TravelingWave::getElementDimensions(double &begin,
                                          double &end) const {
     begin = -0.5 * PeriodLength_m;
-    end = begin + length_m;
+    end = begin + getElementLength();
 }
 
 ElementBase::ElementType TravelingWave::getType() const {
diff --git a/src/Classic/AbsBeamline/TravelingWave.h b/src/Classic/AbsBeamline/TravelingWave.h
index 9d581e104..e82e9ea67 100644
--- a/src/Classic/AbsBeamline/TravelingWave.h
+++ b/src/Classic/AbsBeamline/TravelingWave.h
@@ -88,7 +88,6 @@ public:
 
     virtual bool isInside(const Vector_t &r) const override;
 
-    virtual double getElementLength() const override;
     virtual void getElementDimensions(double &begin,
                                       double &end) const override;
 
@@ -226,7 +225,7 @@ CoordinateSystemTrafo TravelingWave::getEdgeToBegin() const {
 
 inline
 CoordinateSystemTrafo TravelingWave::getEdgeToEnd() const {
-    CoordinateSystemTrafo ret(Vector_t(0, 0, -0.5 * PeriodLength_m + length_m),
+    CoordinateSystemTrafo ret(Vector_t(0, 0, -0.5 * PeriodLength_m + getElementLength()),
                               Quaternion(1, 0, 0, 0));
     return ret;
 }
diff --git a/src/Classic/BeamlineGeometry/Euclid3DGeometry.cpp b/src/Classic/BeamlineGeometry/Euclid3DGeometry.cpp
index 97b2920e0..9234dee4e 100644
--- a/src/Classic/BeamlineGeometry/Euclid3DGeometry.cpp
+++ b/src/Classic/BeamlineGeometry/Euclid3DGeometry.cpp
@@ -29,6 +29,7 @@
 
 #include "Utilities/GeneralClassicException.h"
 #include <cmath>
+#include <algorithm>
 
 Euclid3DGeometry::Euclid3DGeometry(Euclid3D transformation)
     : BGeometryBase(), transformation_m(transformation) {
@@ -57,6 +58,10 @@ double Euclid3DGeometry::getElementLength() const {
 }
 
 void Euclid3DGeometry::setElementLength(double length) {
+    if (length < 0.0) {
+        throw GeneralClassicException("Euclid3DGeometry::setElementLength",
+                                      "The length of an element has to be positive");
+    }
     Vector3D newVector = transformation_m.getVector()*(length/getArcLength());
     transformation_m.setDisplacement(newVector);
 }
@@ -67,4 +72,4 @@ Euclid3D Euclid3DGeometry::getTransform(double /*fromS*/, double /*toS*/) const
 
 Euclid3D Euclid3DGeometry::getTotalTransform() const {
     return transformation_m;
-}
+}
\ No newline at end of file
diff --git a/src/Classic/BeamlineGeometry/PlanarArcGeometry.cpp b/src/Classic/BeamlineGeometry/PlanarArcGeometry.cpp
index 3b1238ea5..e4da5f3f3 100644
--- a/src/Classic/BeamlineGeometry/PlanarArcGeometry.cpp
+++ b/src/Classic/BeamlineGeometry/PlanarArcGeometry.cpp
@@ -20,8 +20,10 @@
 
 #include "BeamlineGeometry/PlanarArcGeometry.h"
 #include "BeamlineGeometry/Euclid3D.h"
-#include <cmath>
+#include "Utilities/GeneralClassicException.h"
 
+#include <cmath>
+#include <algorithm>
 
 // File scope function for calculating general transformations around arcs.
 namespace {
@@ -81,6 +83,10 @@ void PlanarArcGeometry::setCurvature(double hh) {
 
 
 void PlanarArcGeometry::setElementLength(double l) {
+    if (l < 0.0) {
+        throw GeneralClassicException("PlanarArcGeometry::setElementLength",
+                                      "The length of an element has to be positive");
+    }
     len = l;
     if(len != 0.0) angle = h * len;
 }
diff --git a/src/Classic/BeamlineGeometry/RBendGeometry.cpp b/src/Classic/BeamlineGeometry/RBendGeometry.cpp
index a2c8047e6..4aae9916a 100644
--- a/src/Classic/BeamlineGeometry/RBendGeometry.cpp
+++ b/src/Classic/BeamlineGeometry/RBendGeometry.cpp
@@ -33,7 +33,7 @@ RBendGeometry::RBendGeometry(double length, double angle):
 
 
 RBendGeometry::RBendGeometry(const RBendGeometry &rhs):
-    StraightGeometry(*this), half_angle(rhs.half_angle)
+    StraightGeometry(rhs), half_angle(rhs.half_angle)
 {}
 
 
@@ -47,11 +47,6 @@ double RBendGeometry::getArcLength() const {
 }
 
 
-double RBendGeometry::getElementLength() const {
-    return StraightGeometry::getElementLength();
-}
-
-
 double RBendGeometry::getBendAngle() const {
     return 2.0 * half_angle;
 }
@@ -94,4 +89,4 @@ Euclid3D RBendGeometry::getExitPatch() const {
     double d = getElementLength() / 4.0 * tan(half_angle / 2.0);
     return
         Euclid3D::translation(- d, 0.0, 0.0) * Euclid3D::YRotation(- half_angle);
-}
+}
\ No newline at end of file
diff --git a/src/Classic/BeamlineGeometry/RBendGeometry.h b/src/Classic/BeamlineGeometry/RBendGeometry.h
index 43e89373b..2e54736fa 100644
--- a/src/Classic/BeamlineGeometry/RBendGeometry.h
+++ b/src/Classic/BeamlineGeometry/RBendGeometry.h
@@ -55,10 +55,6 @@ public:
     //  design orbit.
     virtual double getArcLength() const;
 
-    /// Get element length.
-    //  Return the straight length of the geometry.
-    virtual double getElementLength() const;
-
     /// Get angle.
     //  Return the total bend angle.
     virtual double getBendAngle() const;
@@ -100,5 +96,4 @@ private:
     double half_angle;
 };
 
-#endif // CLASSIC_RBendGeometry_HH
-
+#endif // CLASSIC_RBendGeometry_HH
\ No newline at end of file
diff --git a/src/Classic/BeamlineGeometry/StraightGeometry.cpp b/src/Classic/BeamlineGeometry/StraightGeometry.cpp
index 46f4a1c96..fbffcd7c8 100644
--- a/src/Classic/BeamlineGeometry/StraightGeometry.cpp
+++ b/src/Classic/BeamlineGeometry/StraightGeometry.cpp
@@ -21,7 +21,9 @@
 
 #include "BeamlineGeometry/StraightGeometry.h"
 #include "BeamlineGeometry/Euclid3D.h"
+#include "Utilities/GeneralClassicException.h"
 
+#include <algorithm>
 
 // Class StraightGeometry.
 // ------------------------------------------------------------------------
@@ -41,7 +43,11 @@ double StraightGeometry::getElementLength() const {
 
 
 void StraightGeometry::setElementLength(double l) {
-    len = l;
+    if (l < 0.0) {
+        throw GeneralClassicException("StraightGeometry::setElementLength",
+                                      "The length of an element has to be positive");
+    }
+    len = std::max(0.0, l);
 }
 
 
@@ -82,8 +88,4 @@ Euclid3D StraightGeometry::getEntranceFrame() const {
 
 Euclid3D StraightGeometry::getExitFrame() const {
     return Euclid3D::translation(0, 0, len / 2.0);
-}
-
-
-
-
+}
\ No newline at end of file
diff --git a/src/Classic/BeamlineGeometry/VarRadiusGeometry.h b/src/Classic/BeamlineGeometry/VarRadiusGeometry.h
index b3cf41ef7..14b67d17e 100644
--- a/src/Classic/BeamlineGeometry/VarRadiusGeometry.h
+++ b/src/Classic/BeamlineGeometry/VarRadiusGeometry.h
@@ -51,10 +51,12 @@
   */
 
 #include "BeamlineGeometry/Geometry.h"
+#include "Utilities/GeneralClassicException.h"
+#include <algorithm>
 
 class VarRadiusGeometry: public BGeometryBase {
 public:
-    /** Build VarRadiusGeometry with given length, centre radius of curvature 
+    /** Build VarRadiusGeometry with given length, centre radius of curvature
      *  and fringe field
      *  \param length -> Length of geometry
      *  \param rho -> Centre radius of curvature of geometry
@@ -171,7 +173,11 @@ inline
 }
 inline
     void VarRadiusGeometry::setElementLength(double length) {
-        length_m = length;
+        if (length < 0.0) {
+            throw GeneralClassicException("VarRadiusGeometry::setElementLength",
+                                          "The length of an element has to be positive");
+        }
+        length_m = std::max(0.0, length);
 }
 inline
     double VarRadiusGeometry::getRadius() const {
@@ -214,5 +220,4 @@ inline
         return getTransform(getOrigin(), getExit());
 }
 
-#endif
-
+#endif
\ No newline at end of file
diff --git a/src/Elements/OpalRBend.cpp b/src/Elements/OpalRBend.cpp
index d15b8b528..326e70c7a 100644
--- a/src/Elements/OpalRBend.cpp
+++ b/src/Elements/OpalRBend.cpp
@@ -67,9 +67,6 @@ void OpalRBend::update() {
     double e1     = Attributes::getReal(itsAttr[E1]);
     RBendGeometry &geometry = bend->getGeometry();
     geometry.setElementLength(length);
-    if (angle < 0) {
-
-    }
     geometry.setBendAngle(angle);
 
     // Define number of slices for map tracking
@@ -106,7 +103,7 @@ void OpalRBend::update() {
     bend->setField(field);
 
     // Set field amplitude or bend angle.
-    if(itsAttr[ANGLE]) {
+    if (itsAttr[ANGLE]) {
         if (bend->isPositioned() && angle < 0.0) {
             e1 = -e1;
             angle = -angle;
@@ -124,14 +121,14 @@ void OpalRBend::update() {
     }
         bend->setEntranceAngle(e1);
 
-    if(itsAttr[ROTATION])
+    if (itsAttr[ROTATION])
         throw OpalException("OpalRBend::update",
                             "ROTATION not supported any more; use PSI instead");
 
 
-    if(itsAttr[FMAPFN])
+    if (itsAttr[FMAPFN])
         bend->setFieldMapFN(Attributes::getString(itsAttr[FMAPFN]));
-    else if(bend->getName() != "RBEND") {
+    else if (bend->getName() != "RBEND") {
         ERRORMSG(bend->getName() << ": No filename for a field map given. "
                  "Will assume the default map "
                  "\"1DPROFILE1-DEFAULT\"."
@@ -140,7 +137,7 @@ void OpalRBend::update() {
     }
 
     // Energy in eV.
-    if(itsAttr[DESIGNENERGY] && Attributes::getReal(itsAttr[DESIGNENERGY]) != 0.0) {
+    if (itsAttr[DESIGNENERGY] && Attributes::getReal(itsAttr[DESIGNENERGY]) != 0.0) {
         bend->setDesignEnergy(Attributes::getReal(itsAttr[DESIGNENERGY]), false);
     } else if (bend->getName() != "RBEND") {
         throw OpalException("OpalRBend::update",
@@ -150,34 +147,29 @@ void OpalRBend::update() {
     double gap = Attributes::getReal(itsAttr[GAP]);
     bend->setFullGap(gap);
 
-    if(itsAttr[APERT])
+    if (itsAttr[APERT])
         throw OpalException("OpalRBend::update",
                             "APERTURE in RBEND not supported; use GAP and HAPERT instead");
 
-    if(itsAttr[HAPERT]) {
+    if (itsAttr[HAPERT]) {
         double hapert = Attributes::getReal(itsAttr[HAPERT]);
         bend->setAperture(ElementBase::RECTANGULAR, std::vector<double>({hapert, gap, 1.0}));
     } else {
         bend->setAperture(ElementBase::RECTANGULAR, std::vector<double>({0.5, gap, 1.0}));
     }
 
-    if(itsAttr[LENGTH])
-        bend->setLength(Attributes::getReal(itsAttr[LENGTH]));
-    else
-        bend->setLength(0.0);
-
-    if(itsAttr[WAKEF] && itsAttr[DESIGNENERGY] && owk_m == NULL) {
+    if (itsAttr[WAKEF] && itsAttr[DESIGNENERGY] && owk_m == NULL) {
         owk_m = (OpalWake::find(Attributes::getString(itsAttr[WAKEF])))->clone(getOpalName() + std::string("_wake"));
         owk_m->initWakefunction(*bend);
         bend->setWake(owk_m->wf_m);
     }
 
-    if(itsAttr[K1])
+    if (itsAttr[K1])
         bend->setK1(Attributes::getReal(itsAttr[K1]));
     else
         bend->setK1(0.0);
 
-    if(itsAttr[PARTICLEMATTERINTERACTION] && parmatint_m == NULL) {
+    if (itsAttr[PARTICLEMATTERINTERACTION] && parmatint_m == NULL) {
         parmatint_m = (ParticleMatterInteraction::find(Attributes::getString(itsAttr[PARTICLEMATTERINTERACTION])))->clone(getOpalName() + std::string("_parmatint"));
         parmatint_m->initParticleMatterInteractionHandler(*bend);
         bend->setParticleMatterInteraction(parmatint_m->handler_m);
diff --git a/src/Elements/OpalRBend3D.cpp b/src/Elements/OpalRBend3D.cpp
index 8c6773e62..9d0c0de3d 100644
--- a/src/Elements/OpalRBend3D.cpp
+++ b/src/Elements/OpalRBend3D.cpp
@@ -128,9 +128,9 @@ void OpalRBend3D::update() {
     }
 
     if(itsAttr[LENGTH]) {
-        bend->setLength(Attributes::getReal(itsAttr[LENGTH]));
+        bend->setElementLength(Attributes::getReal(itsAttr[LENGTH]));
     } else
-        bend->setLength(0.0);
+        bend->setElementLength(0.0);
 
     if(itsAttr[WAKEF] && itsAttr[DESIGNENERGY] && owk_m == NULL) {
         owk_m = (OpalWake::find(Attributes::getString(itsAttr[WAKEF])))->clone(getOpalName() + std::string("_wake"));
diff --git a/src/Elements/OpalSBend.cpp b/src/Elements/OpalSBend.cpp
index 287603ffa..9d27d9b6c 100644
--- a/src/Elements/OpalSBend.cpp
+++ b/src/Elements/OpalSBend.cpp
@@ -166,11 +166,6 @@ void OpalSBend::update() {
         bend->setAperture(ElementBase::RECTANGULAR, std::vector<double>({0.5, gap, 1.0}));
     }
 
-    if(itsAttr[LENGTH])
-        bend->setLength(Attributes::getReal(itsAttr[LENGTH]));
-    else
-        bend->setLength(0.0);
-
     if(itsAttr[WAKEF] && itsAttr[DESIGNENERGY] && owk_m == NULL) {
         owk_m = (OpalWake::find(Attributes::getString(itsAttr[WAKEF])))->clone(getOpalName() + std::string("_wake"));
         owk_m->initWakefunction(*bend);
diff --git a/src/Track/TrackCmd.cpp b/src/Track/TrackCmd.cpp
index 3bdd72058..98c3266dd 100644
--- a/src/Track/TrackCmd.cpp
+++ b/src/Track/TrackCmd.cpp
@@ -23,7 +23,7 @@
 #include "Structure/Beam.h"
 #include "Track/Track.h"
 #include "Track/TrackParser.h"
-
+#include "Utilities/OpalException.h"
 
 // Class Track
 // ------------------------------------------------------------------------
@@ -78,7 +78,7 @@ TrackCmd::TrackCmd():
                      ("ZSTOP", "Defines a z-location [m], after which the simulation stops when the last particles passes");
     itsAttr[TIMEINTEGRATOR] = Attributes::makeString
                               ("TIMEINTEGRATOR", "Name of time integrator to be used", "RK-4");
-    
+
     itsAttr[MAP_ORDER] = Attributes::makeReal
                      ("MAP_ORDER", "Truncation order of maps for ThickTracker (default: 1, i.e. linear)", 1);
 
@@ -103,11 +103,17 @@ TrackCmd *TrackCmd::clone(const std::string &name) {
 }
 
 std::vector<double> TrackCmd::getDT() const {
-    std::vector<double> dt = Attributes::getRealArray(itsAttr[DT]);
-    if (dt.size() == 0) {
-        dt.push_back(1e-12);
+    std::vector<double> dTs = Attributes::getRealArray(itsAttr[DT]);
+    if (dTs.size() == 0) {
+        dTs.push_back(1e-12);
+    }
+    for (double dt : dTs) {
+        if (dt < 0.0) {
+            throw OpalException("TrackCmd::getDT",
+                                "The time steps provided with DT have to be positive");
+        }
     }
-    return dt;
+    return dTs;
 }
 
 double TrackCmd::getDTSCINIT() const {
@@ -141,11 +147,12 @@ std::vector<unsigned long long> TrackCmd::getMAXSTEPS() const {
     if (maxsteps_d.size() == 0) {
         maxsteps_i.push_back(10ul);
     }
-    for (auto it = maxsteps_d.begin(); it != maxsteps_d.end(); ++ it) {
-        if (*it < 0) {
-            maxsteps_i.push_back(10);
+    for (double numSteps : maxsteps_d) {
+        if (numSteps < 0) {
+            throw OpalException("TrackCmd::getMAXSTEPS",
+                                "The number of steps provided with MAXSTEPS has to be positive");
         } else {
-            unsigned long long value = *it;
+            unsigned long long value = numSteps;
             maxsteps_i.push_back(value);
         }
     }
@@ -205,9 +212,9 @@ void TrackCmd::execute() {
     Track::block = new Track(use, beam->getReference(), dt, maxsteps,
                              stepsperturn, zstart, zstop,
                              timeintegrator, t0, getDTSCINIT(), getDTAU());
-    
+
     Track::block->truncOrder = (int)Attributes::getReal(itsAttr[MAP_ORDER]);
-    
+
     Track::block->parser.run();
 
     // Clean up.
-- 
GitLab