Back to home page

EIC code displayed by LXR

 
 

    


File indexing completed on 2025-10-14 08:00:08

0001 // This file is part of the ACTS project.
0002 //
0003 // Copyright (C) 2016 CERN for the benefit of the ACTS project
0004 //
0005 // This Source Code Form is subject to the terms of the Mozilla Public
0006 // License, v. 2.0. If a copy of the MPL was not distributed with this
0007 // file, You can obtain one at https://mozilla.org/MPL/2.0/.
0008 
0009 #pragma once
0010 
0011 #include "Acts/EventData/MultiTrajectory.hpp"
0012 #include "Acts/EventData/MultiTrajectoryHelpers.hpp"
0013 #include "Acts/EventData/SourceLink.hpp"
0014 #include "Acts/EventData/TrackParameters.hpp"
0015 #include "Acts/EventData/TrackStateType.hpp"
0016 #include "Acts/EventData/VectorMultiTrajectory.hpp"
0017 #include "Acts/Geometry/GeometryContext.hpp"
0018 #include "Acts/MagneticField/MagneticFieldContext.hpp"
0019 #include "Acts/Propagator/ActorList.hpp"
0020 #include "Acts/Propagator/DirectNavigator.hpp"
0021 #include "Acts/Propagator/PropagatorOptions.hpp"
0022 #include "Acts/Propagator/StandardAborters.hpp"
0023 #include "Acts/Propagator/detail/LoopProtection.hpp"
0024 #include "Acts/Propagator/detail/PointwiseMaterialInteraction.hpp"
0025 #include "Acts/TrackFitting/KalmanFitterError.hpp"
0026 #include "Acts/TrackFitting/detail/KalmanUpdateHelpers.hpp"
0027 #include "Acts/TrackFitting/detail/VoidFitterComponents.hpp"
0028 #include "Acts/Utilities/CalibrationContext.hpp"
0029 #include "Acts/Utilities/Delegate.hpp"
0030 #include "Acts/Utilities/Intersection.hpp"
0031 #include "Acts/Utilities/Logger.hpp"
0032 #include "Acts/Utilities/Result.hpp"
0033 #include "Acts/Utilities/TrackHelpers.hpp"
0034 
0035 #include <functional>
0036 #include <limits>
0037 #include <map>
0038 #include <memory>
0039 #include <type_traits>
0040 
0041 namespace Acts {
0042 
0043 /// Strategy for selecting track states when reaching target surface in Kalman
0044 /// filter
0045 enum class KalmanFitterTargetSurfaceStrategy {
0046   /// Use the first trackstate to reach target surface
0047   first,
0048   /// Use the last trackstate to reach target surface
0049   last,
0050   /// Use the first or last trackstate to reach target surface depending on the
0051   /// distance
0052   firstOrLast,
0053 };
0054 
0055 /// Extension struct which holds delegates to customise the KF behavior
0056 template <typename traj_t>
0057 struct KalmanFitterExtensions {
0058   /// Type alias for track state proxy from trajectory
0059   using TrackStateProxy = typename traj_t::TrackStateProxy;
0060   /// Type alias for const track state proxy from trajectory
0061   using ConstTrackStateProxy = typename traj_t::ConstTrackStateProxy;
0062   /// Type alias for track parameters from track state proxy
0063   using Parameters = typename TrackStateProxy::Parameters;
0064 
0065   /// Type alias for measurement calibrator delegate
0066   using Calibrator =
0067       Delegate<void(const GeometryContext&, const CalibrationContext&,
0068                     const SourceLink&, TrackStateProxy)>;
0069 
0070   /// Type alias for track smoothing delegate
0071   using Smoother = Delegate<Result<void>(const GeometryContext&, traj_t&,
0072                                          std::size_t, const Logger&)>;
0073 
0074   /// Type alias for Kalman filter update delegate
0075   using Updater = Delegate<Result<void>(const GeometryContext&, TrackStateProxy,
0076                                         const Logger&)>;
0077 
0078   /// Type alias for outlier detection delegate
0079   using OutlierFinder = Delegate<bool(ConstTrackStateProxy)>;
0080 
0081   /// Type alias for reverse filtering decision delegate
0082   using ReverseFilteringLogic = Delegate<bool(ConstTrackStateProxy)>;
0083 
0084   /// The Calibrator is a dedicated calibration algorithm that allows
0085   /// to calibrate measurements using track information, this could be
0086   /// e.g. sagging for wires, module deformations, etc.
0087   Calibrator calibrator;
0088 
0089   /// The updater incorporates measurement information into the track parameters
0090   Updater updater;
0091 
0092   /// The smoother back-propagates measurement information along the track
0093   Smoother smoother;
0094 
0095   /// Determines whether a measurement is supposed to be considered as an
0096   /// outlier
0097   OutlierFinder outlierFinder;
0098 
0099   /// Decides whether the smoothing stage uses linearized transport or full
0100   /// reverse propagation
0101   ReverseFilteringLogic reverseFilteringLogic;
0102 
0103   /// Retrieves the associated surface from a source link
0104   SourceLinkSurfaceAccessor surfaceAccessor;
0105 
0106   /// Default constructor which connects the default void components
0107   KalmanFitterExtensions() {
0108     calibrator.template connect<&detail::voidFitterCalibrator<traj_t>>();
0109     updater.template connect<&detail::voidFitterUpdater<traj_t>>();
0110     smoother.template connect<&detail::voidFitterSmoother<traj_t>>();
0111     outlierFinder.template connect<&detail::voidOutlierFinder<traj_t>>();
0112     reverseFilteringLogic
0113         .template connect<&detail::voidReverseFilteringLogic<traj_t>>();
0114     surfaceAccessor.connect<&detail::voidSurfaceAccessor>();
0115   }
0116 };
0117 
0118 /// Combined options for the Kalman fitter.
0119 ///
0120 /// @tparam traj_t The trajectory type
0121 template <typename traj_t>
0122 struct KalmanFitterOptions {
0123   /// PropagatorOptions with context.
0124   ///
0125   /// @param gctx The geometry context for this fit
0126   /// @param mctx The magnetic context for this fit
0127   /// @param cctx The calibration context for this fit
0128   /// @param extensions_ The KF extensions
0129   /// @param pOptions The plain propagator options
0130   /// @param rSurface The reference surface for the fit to be expressed at
0131   /// @param mScattering Whether to include multiple scattering
0132   /// @param eLoss Whether to include energy loss
0133   /// @param rFiltering Whether to run filtering in reversed direction as smoothing
0134   /// @param rfScaling Scale factor for the covariance matrix before the backward filtering
0135   /// @param freeToBoundCorrection_ Correction for non-linearity effect during transform from free to bound
0136   KalmanFitterOptions(const GeometryContext& gctx,
0137                       const MagneticFieldContext& mctx,
0138                       std::reference_wrapper<const CalibrationContext> cctx,
0139                       KalmanFitterExtensions<traj_t> extensions_,
0140                       const PropagatorPlainOptions& pOptions,
0141                       const Surface* rSurface = nullptr,
0142                       bool mScattering = true, bool eLoss = true,
0143                       bool rFiltering = false, double rfScaling = 1.0,
0144                       const FreeToBoundCorrection& freeToBoundCorrection_ =
0145                           FreeToBoundCorrection(false))
0146       : geoContext(gctx),
0147         magFieldContext(mctx),
0148         calibrationContext(cctx),
0149         extensions(extensions_),
0150         propagatorPlainOptions(pOptions),
0151         referenceSurface(rSurface),
0152         multipleScattering(mScattering),
0153         energyLoss(eLoss),
0154         reversedFiltering(rFiltering),
0155         reversedFilteringCovarianceScaling(rfScaling),
0156         freeToBoundCorrection(freeToBoundCorrection_) {}
0157   /// Contexts are required and the options must not be default-constructible.
0158   KalmanFitterOptions() = delete;
0159 
0160   /// Context object for the geometry
0161   std::reference_wrapper<const GeometryContext> geoContext;
0162   /// Context object for the magnetic field
0163   std::reference_wrapper<const MagneticFieldContext> magFieldContext;
0164   /// context object for the calibration
0165   std::reference_wrapper<const CalibrationContext> calibrationContext;
0166 
0167   /// Extensions for calibration and outlier finding
0168   KalmanFitterExtensions<traj_t> extensions;
0169 
0170   /// The trivial propagator options
0171   PropagatorPlainOptions propagatorPlainOptions;
0172 
0173   /// The reference Surface
0174   const Surface* referenceSurface = nullptr;
0175 
0176   /// Strategy to propagate to reference surface
0177   KalmanFitterTargetSurfaceStrategy referenceSurfaceStrategy =
0178       KalmanFitterTargetSurfaceStrategy::firstOrLast;
0179 
0180   /// Whether to consider multiple scattering
0181   bool multipleScattering = true;
0182 
0183   /// Whether to consider energy loss
0184   bool energyLoss = true;
0185 
0186   /// Whether to run filtering in reversed direction overwrite the
0187   /// ReverseFilteringLogic
0188   bool reversedFiltering = false;
0189 
0190   /// Factor by which the covariance of the input of the reversed filtering is
0191   /// scaled. This is only used in the backwardfiltering (if reversedFiltering
0192   /// is true or if the ReverseFilteringLogic return true for the track of
0193   /// interest)
0194   double reversedFilteringCovarianceScaling = 1.0;
0195 
0196   /// Whether to include non-linear correction during global to local
0197   /// transformation
0198   FreeToBoundCorrection freeToBoundCorrection;
0199 };
0200 
0201 template <typename traj_t>
0202 struct KalmanFitterResult {
0203   /// Fitted states that the actor has handled.
0204   traj_t* fittedStates{nullptr};
0205 
0206   /// This is the index of the 'tip' of the track stored in multitrajectory.
0207   /// This corresponds to the last measurement state in the multitrajectory.
0208   /// Since this KF only stores one trajectory, it is unambiguous.
0209   /// MultiTrajectoryTraits::kInvalid is the start of a trajectory.
0210   std::size_t lastMeasurementIndex = MultiTrajectoryTraits::kInvalid;
0211 
0212   /// This is the index of the 'tip' of the states stored in multitrajectory.
0213   /// This corresponds to the last state in the multitrajectory.
0214   /// Since this KF only stores one trajectory, it is unambiguous.
0215   /// MultiTrajectoryTraits::kInvalid is the start of a trajectory.
0216   std::size_t lastTrackIndex = MultiTrajectoryTraits::kInvalid;
0217 
0218   /// The optional Parameters at the provided surface
0219   std::optional<BoundTrackParameters> fittedParameters;
0220 
0221   /// Counter for states with non-outlier measurements
0222   std::size_t measurementStates = 0;
0223 
0224   /// Counter for measurements holes
0225   /// A hole correspond to a surface with an associated detector element with no
0226   /// associated measurement. Holes are only taken into account if they are
0227   /// between the first and last measurements.
0228   std::size_t measurementHoles = 0;
0229 
0230   /// Counter for handled states
0231   std::size_t processedStates = 0;
0232 
0233   /// Indicator if smoothing has been done.
0234   bool smoothed = false;
0235 
0236   /// Indicator if navigation direction has been reversed
0237   bool reversed = false;
0238 
0239   /// Indicator if track fitting has been done
0240   bool finished = false;
0241 
0242   /// Measurement surfaces without hits
0243   std::vector<const Surface*> missedActiveSurfaces;
0244 
0245   /// Measurement surfaces handled in both forward and backward filtering
0246   std::vector<const Surface*> passedAgainSurfaces;
0247 
0248   /// Last encountered error
0249   Result<void> result{Result<void>::success()};
0250 
0251   /// Path limit aborter
0252   PathLimitReached pathLimitReached;
0253 };
0254 
0255 /// Kalman fitter implementation.
0256 ///
0257 /// @tparam propagator_t Type of the propagation class
0258 ///
0259 /// The Kalman filter contains an Actor and a Sequencer sub-class.
0260 /// The Sequencer has to be part of the Navigator of the Propagator
0261 /// in order to initialize and provide the measurement surfaces.
0262 ///
0263 /// The Actor is part of the Propagation call and does the Kalman update
0264 /// and eventually the smoothing.  Updater, Smoother and Calibrator are
0265 /// given to the Actor for further use:
0266 /// - The Updater is the implemented kalman updater formalism, it
0267 ///   runs via a visitor pattern through the measurements.
0268 /// - The Smoother is called at the end of the filtering by the Actor.
0269 ///
0270 /// Measurements are not required to be ordered for the KalmanFilter,
0271 /// measurement ordering needs to be figured out by the navigation of
0272 /// the propagator.
0273 ///
0274 /// The void components are provided mainly for unit testing.
0275 template <typename propagator_t, typename traj_t>
0276 class KalmanFitter {
0277   /// The navigator type
0278   using KalmanNavigator = typename propagator_t::Navigator;
0279 
0280   /// The navigator has DirectNavigator type or not
0281   static constexpr bool isDirectNavigator =
0282       std::is_same_v<KalmanNavigator, DirectNavigator>;
0283 
0284  public:
0285   /// Constructor with propagator and logger
0286   /// @param pPropagator Propagator instance for track propagation
0287   /// @param _logger Logger for diagnostic output
0288   explicit KalmanFitter(propagator_t pPropagator,
0289                         std::unique_ptr<const Logger> _logger =
0290                             getDefaultLogger("KalmanFitter", Logging::INFO))
0291       : m_propagator(std::move(pPropagator)),
0292         m_logger{std::move(_logger)},
0293         m_actorLogger{m_logger->cloneWithSuffix("Actor")} {}
0294 
0295  private:
0296   /// The propagator for the transport and material update
0297   propagator_t m_propagator;
0298 
0299   /// The logger instance
0300   std::unique_ptr<const Logger> m_logger;
0301   std::unique_ptr<const Logger> m_actorLogger;
0302 
0303   const Logger& logger() const { return *m_logger; }
0304 
0305   /// @brief Propagator Actor plugin for the KalmanFilter
0306   ///
0307   /// @tparam parameters_t The type of parameters used for "local" parameters.
0308   /// @tparam calibrator_t The type of calibrator
0309   /// @tparam outlier_finder_t Type of the outlier finder class
0310   ///
0311   /// The KalmanActor does not rely on the measurements to be
0312   /// sorted along the track.
0313   template <typename parameters_t>
0314   class Actor {
0315    public:
0316     /// Broadcast the result_type
0317     using result_type = KalmanFitterResult<traj_t>;
0318 
0319     /// The target surface aboter
0320     SurfaceReached targetReached{std::numeric_limits<double>::lowest()};
0321 
0322     /// Strategy to propagate to target surface
0323     KalmanFitterTargetSurfaceStrategy targetSurfaceStrategy =
0324         KalmanFitterTargetSurfaceStrategy::firstOrLast;
0325 
0326     /// Allows retrieving measurements for a surface
0327     const std::map<GeometryIdentifier, SourceLink>* inputMeasurements = nullptr;
0328 
0329     /// Whether to consider multiple scattering.
0330     bool multipleScattering = true;
0331 
0332     /// Whether to consider energy loss.
0333     bool energyLoss = true;
0334 
0335     /// Whether run reversed filtering
0336     bool reversedFiltering = false;
0337 
0338     /// Scale the covariance before the reversed filtering
0339     double reversedFilteringCovarianceScaling = 1.0;
0340 
0341     /// Whether to include non-linear correction during global to local
0342     /// transformation
0343     FreeToBoundCorrection freeToBoundCorrection;
0344 
0345     /// Input MultiTrajectory
0346     std::shared_ptr<traj_t> outputStates;
0347 
0348     KalmanFitterExtensions<traj_t> extensions;
0349 
0350     /// Calibration context for the fit
0351     const CalibrationContext* calibrationContext{nullptr};
0352 
0353     /// End of world aborter
0354     EndOfWorldReached endOfWorldReached;
0355 
0356     /// Volume constraint aborter
0357     VolumeConstraintAborter volumeConstraintAborter;
0358 
0359     /// The logger instance
0360     const Logger* actorLogger{nullptr};
0361 
0362     /// Logger helper
0363     const Logger& logger() const { return *actorLogger; }
0364 
0365     /// @brief Kalman actor operation
0366     ///
0367     /// @tparam propagator_state_t is the type of Propagator state
0368     /// @tparam stepper_t Type of the stepper
0369     /// @tparam navigator_t Type of the navigator
0370     ///
0371     /// @param state is the mutable propagator state object
0372     /// @param stepper The stepper in use
0373     /// @param navigator The navigator in use
0374     /// @param result is the mutable result state object
0375     template <typename propagator_state_t, typename stepper_t,
0376               typename navigator_t>
0377     void act(propagator_state_t& state, const stepper_t& stepper,
0378              const navigator_t& navigator, result_type& result,
0379              const Logger& /*logger*/) const {
0380       assert(result.fittedStates && "No MultiTrajectory set");
0381 
0382       if (result.finished) {
0383         return;
0384       }
0385 
0386       ACTS_VERBOSE("KalmanFitter step at pos: "
0387                    << stepper.position(state.stepping).transpose()
0388                    << " dir: " << stepper.direction(state.stepping).transpose()
0389                    << " momentum: "
0390                    << stepper.absoluteMomentum(state.stepping));
0391 
0392       // Initialize path limit reached aborter
0393       if (result.pathLimitReached.internalLimit ==
0394           std::numeric_limits<double>::max()) {
0395         detail::setupLoopProtection(state, stepper, result.pathLimitReached,
0396                                     true, logger());
0397       }
0398 
0399       // Update:
0400       // - Waiting for a current surface
0401       const Surface* surface = navigator.currentSurface(state.navigation);
0402       if (surface != nullptr) {
0403         // Check if the surface is in the measurement map
0404         // -> Get the measurement / calibrate
0405         // -> Create the predicted state
0406         // -> Check outlier behavior, if non-outlier:
0407         // -> Perform the kalman update
0408         // -> Fill track state information & update stepper information
0409 
0410         if (!result.smoothed && !result.reversed) {
0411           ACTS_VERBOSE("Perform " << state.options.direction << " filter step");
0412           auto res = filter(surface, state, stepper, navigator, result);
0413           if (!res.ok()) {
0414             ACTS_ERROR("Error in " << state.options.direction
0415                                    << " filter: " << res.error());
0416             result.result = res.error();
0417           }
0418         }
0419         if (result.reversed) {
0420           ACTS_VERBOSE("Perform " << state.options.direction << " filter step");
0421           auto res = reversedFilter(surface, state, stepper, navigator, result);
0422           if (!res.ok()) {
0423             ACTS_ERROR("Error in " << state.options.direction
0424                                    << " filter: " << res.error());
0425             result.result = res.error();
0426           }
0427         }
0428       }
0429 
0430       // Finalization:
0431       // when all track states have been handled or the navigation is breaked,
0432       // reset navigation&stepping before run reversed filtering or
0433       // proceed to run smoothing
0434       if (!result.smoothed && !result.reversed) {
0435         const bool isTrackComplete =
0436             result.measurementStates == inputMeasurements->size();
0437         const bool isEndOfWorldReached =
0438             endOfWorldReached.checkAbort(state, stepper, navigator, logger());
0439         const bool isVolumeConstraintReached =
0440             volumeConstraintAborter.checkAbort(state, stepper, navigator,
0441                                                logger());
0442         const bool isPathLimitReached = result.pathLimitReached.checkAbort(
0443             state, stepper, navigator, logger());
0444         if (isTrackComplete || isEndOfWorldReached ||
0445             isVolumeConstraintReached || isPathLimitReached) {
0446           if (result.lastMeasurementIndex == MultiTrajectoryTraits::kInvalid) {
0447             ACTS_INFO(
0448                 "No measurements were found on the track, cannot proceed "
0449                 "to smoothing or reversed filtering.");
0450             result.finished = true;
0451             return;
0452           }
0453 
0454           // Remove the missing surfaces that occur after the last measurement
0455           result.missedActiveSurfaces.resize(result.measurementHoles);
0456           // now get track state proxy for the outlier logic
0457           typename traj_t::ConstTrackStateProxy trackStateProxy{
0458               result.fittedStates->getTrackState(result.lastMeasurementIndex)};
0459           const bool doReverseFiltering =
0460               reversedFiltering ||
0461               extensions.reverseFilteringLogic(trackStateProxy);
0462           if (doReverseFiltering) {
0463             // Start to run reversed filtering:
0464             // Reverse navigation direction and reset navigation and stepping
0465             // state to last measurement
0466             ACTS_VERBOSE("Reverse navigation direction.");
0467             auto res = reverse(state, stepper, navigator, result);
0468             if (!res.ok()) {
0469               ACTS_ERROR("Error in reversing navigation: " << res.error());
0470               result.result = res.error();
0471             }
0472           } else {
0473             // --> Search the starting state to run the smoothing
0474             // --> Call the smoothing
0475             // --> Set a stop condition when all track states have been handled
0476             ACTS_VERBOSE("Finalize/run smoothing");
0477             auto res = finalize(state, stepper, navigator, result);
0478             if (!res.ok()) {
0479               ACTS_ERROR("Error in finalize: " << res.error());
0480               result.result = res.error();
0481             }
0482           }
0483         }
0484       }
0485 
0486       // Post-finalization:
0487       // - Progress to target/reference surface and built the final track
0488       // parameters
0489       if (result.smoothed || result.reversed) {
0490         if (result.smoothed) {
0491           // Update state and stepper with material effects
0492           // Only for smoothed as reverse filtering will handle this separately
0493           materialInteractor(navigator.currentSurface(state.navigation), state,
0494                              stepper, navigator,
0495                              MaterialUpdateStage::FullUpdate);
0496         }
0497 
0498         if (targetReached.surface == nullptr) {
0499           // If no target surface provided:
0500           // -> Return an error when using reversed filtering mode
0501           // -> Fitting is finished here
0502           if (result.reversed) {
0503             ACTS_ERROR(
0504                 "The target surface needed for aborting reversed propagation "
0505                 "is not provided");
0506             result.result =
0507                 Result<void>(KalmanFitterError::ReversePropagationFailed);
0508           } else {
0509             ACTS_VERBOSE(
0510                 "No target surface set. Completing without fitted track "
0511                 "parameter");
0512             // Remember the track fitting is done
0513             result.finished = true;
0514           }
0515         } else if (targetReached.checkAbort(state, stepper, navigator,
0516                                             logger())) {
0517           ACTS_VERBOSE("Completing with fitted track parameter");
0518           // Transport & bind the parameter to the final surface
0519           auto res = stepper.boundState(state.stepping, *targetReached.surface,
0520                                         true, freeToBoundCorrection);
0521           if (!res.ok()) {
0522             ACTS_ERROR("Error in " << state.options.direction
0523                                    << " filter: " << res.error());
0524             result.result = res.error();
0525             return;
0526           }
0527           auto& fittedState = *res;
0528           // Assign the fitted parameters
0529           result.fittedParameters = std::get<BoundTrackParameters>(fittedState);
0530 
0531           // Reset smoothed status of states missed in reversed filtering
0532           if (result.reversed) {
0533             result.fittedStates->applyBackwards(
0534                 result.lastMeasurementIndex, [&](auto trackState) {
0535                   auto fSurface = &trackState.referenceSurface();
0536                   if (!rangeContainsValue(result.passedAgainSurfaces,
0537                                           fSurface)) {
0538                     // If reversed filtering missed this surface, then there is
0539                     // no smoothed parameter
0540                     trackState.unset(TrackStatePropMask::Smoothed);
0541                     if (trackState.typeFlags().test(
0542                             TrackStateFlag::MeasurementFlag)) {
0543                       trackState.typeFlags().set(TrackStateFlag::OutlierFlag);
0544                     }
0545                   }
0546                 });
0547           }
0548           // Remember the track fitting is done
0549           result.finished = true;
0550         }
0551       }
0552     }
0553 
0554     template <typename propagator_state_t, typename stepper_t,
0555               typename navigator_t>
0556     bool checkAbort(propagator_state_t& /*state*/, const stepper_t& /*stepper*/,
0557                     const navigator_t& /*navigator*/, const result_type& result,
0558                     const Logger& /*logger*/) const {
0559       return (!result.result.ok() || result.finished);
0560     }
0561 
0562     /// @brief Kalman actor operation: reverse direction
0563     ///
0564     /// @tparam propagator_state_t is the type of Propagator state
0565     /// @tparam stepper_t Type of the stepper
0566     /// @tparam navigator_t Type of the navigator
0567     ///
0568     /// @param state is the mutable propagator state object
0569     /// @param stepper The stepper in use
0570     /// @param navigator The navigator in use
0571     /// @param result is the mutable result state object
0572     template <typename propagator_state_t, typename stepper_t,
0573               typename navigator_t>
0574     Result<void> reverse(propagator_state_t& state, const stepper_t& stepper,
0575                          const navigator_t& navigator,
0576                          result_type& result) const {
0577       // Check if there is a measurement on track
0578       if (result.lastMeasurementIndex == MultiTrajectoryTraits::kInvalid) {
0579         ACTS_ERROR("No point to reverse for a track without measurements.");
0580         return KalmanFitterError::ReversePropagationFailed;
0581       }
0582 
0583       // Remember the navigation direction has been reversed
0584       result.reversed = true;
0585 
0586       // Reverse navigation direction
0587       state.options.direction = state.options.direction.invert();
0588 
0589       // Reset propagator options
0590       // TODO Not sure if reset of pathLimit during propagation makes any sense
0591       state.options.pathLimit =
0592           state.options.direction * std::abs(state.options.pathLimit);
0593 
0594       // Get the last measurement state and reset navigation&stepping state
0595       // based on information on this state
0596       auto st = result.fittedStates->getTrackState(result.lastMeasurementIndex);
0597 
0598       // Update the stepping state
0599       stepper.initialize(
0600           state.stepping, st.filtered(),
0601           reversedFilteringCovarianceScaling * st.filteredCovariance(),
0602           stepper.particleHypothesis(state.stepping), st.referenceSurface());
0603 
0604       // For the last measurement state, smoothed is filtered
0605       st.smoothed() = st.filtered();
0606       st.smoothedCovariance() = st.filteredCovariance();
0607       result.passedAgainSurfaces.push_back(&st.referenceSurface());
0608 
0609       // Reset navigation state
0610       // We do not need to specify a target here since this will be handled
0611       // separately in the KF actor
0612       state.navigation.options.startSurface = &st.referenceSurface();
0613       state.navigation.options.targetSurface = nullptr;
0614       auto navInitRes = navigator.initialize(
0615           state.navigation, stepper.position(state.stepping),
0616           stepper.direction(state.stepping), state.options.direction);
0617       if (!navInitRes.ok()) {
0618         return navInitRes.error();
0619       }
0620 
0621       // Update material effects for last measurement state in reversed
0622       // direction
0623       materialInteractor(navigator.currentSurface(state.navigation), state,
0624                          stepper, navigator, MaterialUpdateStage::FullUpdate);
0625 
0626       // Set path limit based on loop protection
0627       detail::setupLoopProtection(state, stepper, result.pathLimitReached, true,
0628                                   logger());
0629 
0630       // Set path limit based on target surface
0631       targetReached.checkAbort(state, stepper, navigator, logger());
0632 
0633       return Result<void>::success();
0634     }
0635 
0636     /// @brief Kalman actor operation: update
0637     ///
0638     /// @tparam propagator_state_t is the type of Propagator state
0639     /// @tparam stepper_t Type of the stepper
0640     /// @tparam navigator_t Type of the navigator
0641     ///
0642     /// @param surface The surface where the update happens
0643     /// @param state The mutable propagator state object
0644     /// @param stepper The stepper in use
0645     /// @param navigator The navigator in use
0646     /// @param result The mutable result state object
0647     template <typename propagator_state_t, typename stepper_t,
0648               typename navigator_t>
0649     Result<void> filter(const Surface* surface, propagator_state_t& state,
0650                         const stepper_t& stepper, const navigator_t& navigator,
0651                         result_type& result) const {
0652       const bool precedingMeasurementExists = result.measurementStates > 0;
0653       const bool surfaceIsSensitive =
0654           surface->associatedDetectorElement() != nullptr;
0655       const bool surfaceHasMaterial = surface->surfaceMaterial() != nullptr;
0656 
0657       // Try to find the surface in the measurement surfaces
0658       auto sourceLinkIt = inputMeasurements->find(surface->geometryId());
0659       if (sourceLinkIt != inputMeasurements->end()) {
0660         // Screen output message
0661         ACTS_VERBOSE("Measurement surface " << surface->geometryId()
0662                                             << " detected.");
0663         // Transport the covariance to the surface
0664         stepper.transportCovarianceToBound(state.stepping, *surface,
0665                                            freeToBoundCorrection);
0666 
0667         // Update state and stepper with pre material effects
0668         materialInteractor(surface, state, stepper, navigator,
0669                            MaterialUpdateStage::PreUpdate);
0670 
0671         // do the kalman update (no need to perform covTransport here, hence no
0672         // point in performing globalToLocal correction)
0673         auto trackStateProxyRes = detail::kalmanHandleMeasurement(
0674             *calibrationContext, state, stepper, extensions, *surface,
0675             sourceLinkIt->second, *result.fittedStates, result.lastTrackIndex,
0676             false, logger());
0677 
0678         if (!trackStateProxyRes.ok()) {
0679           return trackStateProxyRes.error();
0680         }
0681 
0682         const auto& trackStateProxy = *trackStateProxyRes;
0683         result.lastTrackIndex = trackStateProxy.index();
0684 
0685         // Update the stepper if it is not an outlier
0686         if (trackStateProxy.typeFlags().test(TrackStateFlag::MeasurementFlag)) {
0687           // Update the stepping state with filtered parameters
0688           ACTS_VERBOSE("Filtering step successful, updated parameters are:\n"
0689                        << trackStateProxy.filtered().transpose());
0690           // update stepping state using filtered parameters after kalman
0691           stepper.update(state.stepping,
0692                          MultiTrajectoryHelpers::freeFiltered(
0693                              state.options.geoContext, trackStateProxy),
0694                          trackStateProxy.filtered(),
0695                          trackStateProxy.filteredCovariance(), *surface);
0696           // We count the state with measurement
0697           ++result.measurementStates;
0698         }
0699 
0700         // Update state and stepper with post material effects
0701         materialInteractor(surface, state, stepper, navigator,
0702                            MaterialUpdateStage::PostUpdate);
0703         // We count the processed state
0704         ++result.processedStates;
0705         // Update the number of holes count only when encountering a
0706         // measurement
0707         result.measurementHoles = result.missedActiveSurfaces.size();
0708         // Since we encountered a measurement update the lastMeasurementIndex to
0709         // the lastTrackIndex.
0710         result.lastMeasurementIndex = result.lastTrackIndex;
0711 
0712       } else if ((precedingMeasurementExists && surfaceIsSensitive) ||
0713                  surfaceHasMaterial) {
0714         // We only create track states here if there is already measurement
0715         // detected or if the surface has material (no holes before the first
0716         // measurement)
0717         auto trackStateProxyRes = detail::kalmanHandleNoMeasurement(
0718             state.stepping, stepper, *surface, *result.fittedStates,
0719             result.lastTrackIndex, true, logger(), precedingMeasurementExists,
0720             freeToBoundCorrection);
0721 
0722         if (!trackStateProxyRes.ok()) {
0723           return trackStateProxyRes.error();
0724         }
0725 
0726         const auto& trackStateProxy = *trackStateProxyRes;
0727         result.lastTrackIndex = trackStateProxy.index();
0728 
0729         if (trackStateProxy.typeFlags().test(TrackStateFlag::HoleFlag)) {
0730           // Count the missed surface
0731           result.missedActiveSurfaces.push_back(surface);
0732         }
0733 
0734         ++result.processedStates;
0735 
0736         // Update state and stepper with (possible) material effects
0737         materialInteractor(surface, state, stepper, navigator,
0738                            MaterialUpdateStage::FullUpdate);
0739       }
0740       return Result<void>::success();
0741     }
0742 
0743     /// @brief Kalman actor operation: update in reversed direction
0744     ///
0745     /// @tparam propagator_state_t is the type of Propagator state
0746     /// @tparam stepper_t Type of the stepper
0747     /// @tparam navigator_t Type of the navigator
0748     ///
0749     /// @param surface The surface where the update happens
0750     /// @param state The mutable propagator state object
0751     /// @param stepper The stepper in use
0752     /// @param navigator The navigator in use
0753     /// @param result The mutable result state object
0754     template <typename propagator_state_t, typename stepper_t,
0755               typename navigator_t>
0756     Result<void> reversedFilter(const Surface* surface,
0757                                 propagator_state_t& state,
0758                                 const stepper_t& stepper,
0759                                 const navigator_t& navigator,
0760                                 result_type& result) const {
0761       // Try to find the surface in the measurement surfaces
0762       auto sourceLinkIt = inputMeasurements->find(surface->geometryId());
0763       if (sourceLinkIt != inputMeasurements->end()) {
0764         // Screen output message
0765         ACTS_VERBOSE("Measurement surface "
0766                      << surface->geometryId()
0767                      << " detected in reversed propagation.");
0768 
0769         // No reversed filtering for last measurement state, but still update
0770         // with material effects
0771         if (result.reversed &&
0772             surface == navigator.startSurface(state.navigation)) {
0773           materialInteractor(surface, state, stepper, navigator,
0774                              MaterialUpdateStage::FullUpdate);
0775           return Result<void>::success();
0776         }
0777 
0778         // Transport the covariance to the surface
0779         stepper.transportCovarianceToBound(state.stepping, *surface,
0780                                            freeToBoundCorrection);
0781 
0782         // Update state and stepper with pre material effects
0783         materialInteractor(surface, state, stepper, navigator,
0784                            MaterialUpdateStage::PreUpdate);
0785 
0786         auto& fittedStates = *result.fittedStates;
0787 
0788         // Add a <mask> TrackState entry multi trajectory. This allocates
0789         // storage for all components, which we will set later.
0790         TrackStatePropMask mask =
0791             TrackStatePropMask::Predicted | TrackStatePropMask::Filtered |
0792             TrackStatePropMask::Smoothed | TrackStatePropMask::Jacobian |
0793             TrackStatePropMask::Calibrated;
0794         const std::size_t currentTrackIndex =
0795             fittedStates.addTrackState(mask, MultiTrajectoryTraits::kInvalid);
0796 
0797         // now get track state proxy back
0798         typename traj_t::TrackStateProxy trackStateProxy =
0799             fittedStates.getTrackState(currentTrackIndex);
0800 
0801         // Set the trackStateProxy components with the state from the ongoing
0802         // propagation
0803         {
0804           trackStateProxy.setReferenceSurface(surface->getSharedPtr());
0805           // Bind the transported state to the current surface
0806           auto res = stepper.boundState(state.stepping, *surface, false,
0807                                         freeToBoundCorrection);
0808           if (!res.ok()) {
0809             return res.error();
0810           }
0811           const auto& [boundParams, jacobian, pathLength] = *res;
0812 
0813           // Fill the track state
0814           trackStateProxy.predicted() = boundParams.parameters();
0815           trackStateProxy.predictedCovariance() = state.stepping.cov;
0816 
0817           trackStateProxy.jacobian() = jacobian;
0818           trackStateProxy.pathLength() = pathLength;
0819         }
0820 
0821         // We have predicted parameters, so calibrate the uncalibrated input
0822         // measurement
0823         extensions.calibrator(state.geoContext, *calibrationContext,
0824                               sourceLinkIt->second, trackStateProxy);
0825 
0826         // If the update is successful, set covariance and
0827         auto updateRes =
0828             extensions.updater(state.geoContext, trackStateProxy, logger());
0829         if (!updateRes.ok()) {
0830           ACTS_ERROR("Backward update step failed: " << updateRes.error());
0831           return updateRes.error();
0832         } else {
0833           // Update the stepping state with filtered parameters
0834           ACTS_VERBOSE(
0835               "Backward filtering step successful, updated parameters are:\n"
0836               << trackStateProxy.filtered().transpose());
0837 
0838           // Fill the smoothed parameter for the existing track state
0839           result.fittedStates->applyBackwards(
0840               result.lastMeasurementIndex, [&](auto trackState) {
0841                 auto fSurface = &trackState.referenceSurface();
0842                 if (fSurface == surface) {
0843                   result.passedAgainSurfaces.push_back(surface);
0844                   trackState.smoothed() = trackStateProxy.filtered();
0845                   trackState.smoothedCovariance() =
0846                       trackStateProxy.filteredCovariance();
0847                   return false;
0848                 }
0849                 return true;
0850               });
0851 
0852           // update stepping state using filtered parameters after kalman
0853           // update We need to (re-)construct a BoundTrackParameters instance
0854           // here, which is a bit awkward.
0855           stepper.update(state.stepping,
0856                          MultiTrajectoryHelpers::freeFiltered(
0857                              state.options.geoContext, trackStateProxy),
0858                          trackStateProxy.filtered(),
0859                          trackStateProxy.filteredCovariance(), *surface);
0860 
0861           // Update state and stepper with post material effects
0862           materialInteractor(surface, state, stepper, navigator,
0863                              MaterialUpdateStage::PostUpdate);
0864         }
0865       } else if (surface->associatedDetectorElement() != nullptr ||
0866                  surface->surfaceMaterial() != nullptr) {
0867         // Transport covariance
0868         if (surface->associatedDetectorElement() != nullptr) {
0869           ACTS_VERBOSE("Detected hole on " << surface->geometryId()
0870                                            << " in reversed filtering");
0871           if (state.stepping.covTransport) {
0872             stepper.transportCovarianceToBound(state.stepping, *surface);
0873           }
0874         } else if (surface->surfaceMaterial() != nullptr) {
0875           ACTS_VERBOSE("Detected in-sensitive surface "
0876                        << surface->geometryId() << " in reversed filtering");
0877           if (state.stepping.covTransport) {
0878             stepper.transportCovarianceToCurvilinear(state.stepping);
0879           }
0880         }
0881         // Not creating bound state here, so need manually reinitialize
0882         // jacobian
0883         stepper.setIdentityJacobian(state.stepping);
0884         if (surface->surfaceMaterial() != nullptr) {
0885           // Update state and stepper with material effects
0886           materialInteractor(surface, state, stepper, navigator,
0887                              MaterialUpdateStage::FullUpdate);
0888         }
0889       }
0890 
0891       return Result<void>::success();
0892     }
0893 
0894     /// @brief Kalman actor operation: material interaction
0895     ///
0896     /// @tparam propagator_state_t is the type of Propagator state
0897     /// @tparam stepper_t Type of the stepper
0898     /// @tparam navigator_t Type of the navigator
0899     ///
0900     /// @param surface The surface where the material interaction happens
0901     /// @param state The mutable propagator state object
0902     /// @param stepper The stepper in use
0903     /// @param navigator The navigator in use
0904     /// @param updateStage The material update stage
0905     ///
0906     template <typename propagator_state_t, typename stepper_t,
0907               typename navigator_t>
0908     void materialInteractor(const Surface* surface, propagator_state_t& state,
0909                             const stepper_t& stepper,
0910                             const navigator_t& navigator,
0911                             const MaterialUpdateStage& updateStage) const {
0912       // Protect against null surface
0913       if (!surface) {
0914         ACTS_VERBOSE(
0915             "Surface is nullptr. Cannot be used for material interaction");
0916         return;
0917       }
0918 
0919       // Indicator if having material
0920       bool hasMaterial = false;
0921 
0922       if (surface && surface->surfaceMaterial()) {
0923         // Prepare relevant input particle properties
0924         detail::PointwiseMaterialInteraction interaction(surface, state,
0925                                                          stepper);
0926         // Evaluate the material properties
0927         if (interaction.evaluateMaterialSlab(state, navigator, updateStage)) {
0928           // Surface has material at this stage
0929           hasMaterial = true;
0930 
0931           // Evaluate the material effects
0932           interaction.evaluatePointwiseMaterialInteraction(multipleScattering,
0933                                                            energyLoss);
0934 
0935           // Screen out material effects info
0936           ACTS_VERBOSE("Material effects on surface: "
0937                        << surface->geometryId()
0938                        << " at update stage: " << updateStage << " are :");
0939           ACTS_VERBOSE("eLoss = "
0940                        << interaction.Eloss << ", "
0941                        << "variancePhi = " << interaction.variancePhi << ", "
0942                        << "varianceTheta = " << interaction.varianceTheta
0943                        << ", "
0944                        << "varianceQoverP = " << interaction.varianceQoverP);
0945 
0946           // Update the state and stepper with material effects
0947           interaction.updateState(state, stepper, addNoise);
0948         }
0949       }
0950 
0951       if (!hasMaterial) {
0952         // Screen out message
0953         ACTS_VERBOSE("No material effects on surface: " << surface->geometryId()
0954                                                         << " at update stage: "
0955                                                         << updateStage);
0956       }
0957     }
0958 
0959     /// @brief Kalman actor operation: finalize
0960     ///
0961     /// @tparam propagator_state_t is the type of Propagator state
0962     /// @tparam stepper_t Type of the stepper
0963     /// @tparam navigator_t Type of the navigator
0964     ///
0965     /// @param state is the mutable propagator state object
0966     /// @param stepper The stepper in use
0967     /// @param navigator The navigator in use
0968     /// @param result is the mutable result state object
0969     template <typename propagator_state_t, typename stepper_t,
0970               typename navigator_t>
0971     Result<void> finalize(propagator_state_t& state, const stepper_t& stepper,
0972                           const navigator_t& navigator,
0973                           result_type& result) const {
0974       // Remember you smoothed the track states
0975       result.smoothed = true;
0976 
0977       // Get the indices of the first states (can be either a measurement or
0978       // material);
0979       std::size_t firstStateIndex = result.lastMeasurementIndex;
0980       // Count track states to be smoothed
0981       std::size_t nStates = 0;
0982       result.fittedStates->applyBackwards(
0983           result.lastMeasurementIndex, [&](auto st) {
0984             bool isMeasurement =
0985                 st.typeFlags().test(TrackStateFlag::MeasurementFlag);
0986             bool isOutlier = st.typeFlags().test(TrackStateFlag::OutlierFlag);
0987             // We are excluding non measurement states and outlier here. Those
0988             // can decrease resolution because only the smoothing corrected the
0989             // very first prediction as filtering is not possible.
0990             if (isMeasurement && !isOutlier) {
0991               firstStateIndex = st.index();
0992             }
0993             nStates++;
0994           });
0995       // Return error if the track has no measurement states (but this should
0996       // not happen)
0997       if (nStates == 0) {
0998         ACTS_ERROR("Smoothing for a track without measurements.");
0999         return KalmanFitterError::SmoothFailed;
1000       }
1001       // Screen output for debugging
1002       ACTS_VERBOSE("Apply smoothing on " << nStates
1003                                          << " filtered track states.");
1004 
1005       // Smooth the track states
1006       auto smoothRes =
1007           extensions.smoother(state.geoContext, *result.fittedStates,
1008                               result.lastMeasurementIndex, logger());
1009       if (!smoothRes.ok()) {
1010         ACTS_ERROR("Smoothing step failed: " << smoothRes.error());
1011         return smoothRes.error();
1012       }
1013 
1014       // Return in case no target surface
1015       if (targetReached.surface == nullptr) {
1016         return Result<void>::success();
1017       }
1018 
1019       // Obtain the smoothed parameters at first/last measurement state
1020       auto firstCreatedState =
1021           result.fittedStates->getTrackState(firstStateIndex);
1022       auto lastCreatedMeasurement =
1023           result.fittedStates->getTrackState(result.lastMeasurementIndex);
1024 
1025       // Lambda to get the intersection of the free params on the target surface
1026       auto target = [&](const FreeVector& freeVector) -> Intersection3D {
1027         return targetReached.surface
1028             ->intersect(
1029                 state.geoContext, freeVector.segment<3>(eFreePos0),
1030                 state.options.direction * freeVector.segment<3>(eFreeDir0),
1031                 BoundaryTolerance::None(), state.options.surfaceTolerance)
1032             .closest();
1033       };
1034 
1035       // The smoothed free params at the first/last measurement state.
1036       // (the first state can also be a material state)
1037       auto firstParams = MultiTrajectoryHelpers::freeSmoothed(
1038           state.options.geoContext, firstCreatedState);
1039       auto lastParams = MultiTrajectoryHelpers::freeSmoothed(
1040           state.options.geoContext, lastCreatedMeasurement);
1041       // Get the intersections of the smoothed free parameters with the target
1042       // surface
1043       const auto firstIntersection = target(firstParams);
1044       const auto lastIntersection = target(lastParams);
1045 
1046       // Update the stepping parameters - in order to progress to destination.
1047       // At the same time, reverse navigation direction for further stepping if
1048       // necessary.
1049       // @note The stepping parameters is updated to the smoothed parameters at
1050       // either the first measurement state or the last measurement state. It
1051       // assumes the target surface is not within the first and the last
1052       // smoothed measurement state. Also, whether the intersection is on
1053       // surface is not checked here.
1054       bool useFirstTrackState = true;
1055       switch (targetSurfaceStrategy) {
1056         case KalmanFitterTargetSurfaceStrategy::first:
1057           useFirstTrackState = true;
1058           break;
1059         case KalmanFitterTargetSurfaceStrategy::last:
1060           useFirstTrackState = false;
1061           break;
1062         case KalmanFitterTargetSurfaceStrategy::firstOrLast:
1063           useFirstTrackState = std::abs(firstIntersection.pathLength()) <=
1064                                std::abs(lastIntersection.pathLength());
1065           break;
1066         default:
1067           ACTS_ERROR("Unknown target surface strategy");
1068           return KalmanFitterError::SmoothFailed;
1069       }
1070       bool reverseDirection = false;
1071       if (useFirstTrackState) {
1072         stepper.initialize(state.stepping, firstCreatedState.smoothed(),
1073                            firstCreatedState.smoothedCovariance(),
1074                            stepper.particleHypothesis(state.stepping),
1075                            firstCreatedState.referenceSurface());
1076         reverseDirection = firstIntersection.pathLength() < 0;
1077       } else {
1078         stepper.initialize(state.stepping, lastCreatedMeasurement.smoothed(),
1079                            lastCreatedMeasurement.smoothedCovariance(),
1080                            stepper.particleHypothesis(state.stepping),
1081                            lastCreatedMeasurement.referenceSurface());
1082         reverseDirection = lastIntersection.pathLength() < 0;
1083       }
1084       // Reverse the navigation direction if necessary
1085       if (reverseDirection) {
1086         ACTS_VERBOSE(
1087             "Reverse navigation direction after smoothing for reaching the "
1088             "target surface");
1089         state.options.direction = state.options.direction.invert();
1090       }
1091       const auto& surface = useFirstTrackState
1092                                 ? firstCreatedState.referenceSurface()
1093                                 : lastCreatedMeasurement.referenceSurface();
1094 
1095       ACTS_VERBOSE(
1096           "Smoothing successful, updating stepping state to smoothed "
1097           "parameters at surface "
1098           << surface.geometryId() << ". Prepared to reach the target surface.");
1099 
1100       // Reset the navigation state to enable propagation towards the target
1101       // surface
1102       // Set targetSurface to nullptr as it is handled manually in the actor
1103       auto navigationOptions = state.navigation.options;
1104       navigationOptions.startSurface = &surface;
1105       navigationOptions.targetSurface = nullptr;
1106       state.navigation = navigator.makeState(navigationOptions);
1107       auto navInitRes = navigator.initialize(
1108           state.navigation, stepper.position(state.stepping),
1109           stepper.direction(state.stepping), state.options.direction);
1110       if (!navInitRes.ok()) {
1111         return navInitRes.error();
1112       }
1113 
1114       return Result<void>::success();
1115     }
1116   };
1117 
1118  public:
1119   /// Fit implementation of the forward filter, calls the
1120   /// the filter and smoother/reversed filter
1121   ///
1122   /// @tparam source_link_iterator_t Iterator type used to pass source links
1123   /// @tparam start_parameters_t Type of the initial parameters
1124   /// @tparam parameters_t Type of parameters used for local parameters
1125   /// @tparam track_container_t Type of the track container
1126   ///
1127   /// @param it Begin iterator for the fittable uncalibrated measurements
1128   /// @param end End iterator for the fittable uncalibrated measurements
1129   /// @param sParameters The initial track parameters
1130   /// @param kfOptions KalmanOptions steering the fit
1131   /// @param trackContainer Input track container storage to append into
1132   /// @note The input measurements are given in the form of @c SourceLink s.
1133   /// It's the calibrators job to turn them into calibrated measurements used in
1134   /// the fit.
1135   ///
1136   /// @return the output as an output track
1137   template <typename source_link_iterator_t, typename start_parameters_t,
1138             typename parameters_t = BoundTrackParameters,
1139             TrackContainerFrontend track_container_t>
1140   Result<typename track_container_t::TrackProxy> fit(
1141       source_link_iterator_t it, source_link_iterator_t end,
1142       const start_parameters_t& sParameters,
1143       const KalmanFitterOptions<traj_t>& kfOptions,
1144       track_container_t& trackContainer) const
1145     requires(!isDirectNavigator)
1146   {
1147     // To be able to find measurements later, we put them into a map
1148     // We need to copy input SourceLinks anyway, so the map can own them.
1149     ACTS_VERBOSE("Preparing " << std::distance(it, end)
1150                               << " input measurements");
1151     std::map<GeometryIdentifier, SourceLink> inputMeasurements;
1152     // for (const auto& sl : sourceLinks) {
1153     for (; it != end; ++it) {
1154       SourceLink sl = *it;
1155       const Surface* surface = kfOptions.extensions.surfaceAccessor(sl);
1156       // @TODO: This can probably change over to surface pointers as keys
1157       auto geoId = surface->geometryId();
1158       inputMeasurements.emplace(geoId, std::move(sl));
1159     }
1160 
1161     // Create the ActorList
1162     using KalmanActor = Actor<parameters_t>;
1163 
1164     using KalmanResult = typename KalmanActor::result_type;
1165     using Actors = ActorList<KalmanActor>;
1166     using PropagatorOptions = typename propagator_t::template Options<Actors>;
1167 
1168     // Create relevant options for the propagation options
1169     PropagatorOptions propagatorOptions(kfOptions.geoContext,
1170                                         kfOptions.magFieldContext);
1171 
1172     // Set the trivial propagator options
1173     propagatorOptions.setPlainOptions(kfOptions.propagatorPlainOptions);
1174 
1175     // Add the measurement surface as external surface to navigator.
1176     // We will try to hit those surface by ignoring boundary checks.
1177     for (const auto& [surfaceId, _] : inputMeasurements) {
1178       propagatorOptions.navigation.insertExternalSurface(surfaceId);
1179     }
1180 
1181     // Catch the actor and set the measurements
1182     auto& kalmanActor = propagatorOptions.actorList.template get<KalmanActor>();
1183     kalmanActor.inputMeasurements = &inputMeasurements;
1184     kalmanActor.targetReached.surface = kfOptions.referenceSurface;
1185     kalmanActor.targetSurfaceStrategy = kfOptions.referenceSurfaceStrategy;
1186     kalmanActor.multipleScattering = kfOptions.multipleScattering;
1187     kalmanActor.energyLoss = kfOptions.energyLoss;
1188     kalmanActor.reversedFiltering = kfOptions.reversedFiltering;
1189     kalmanActor.reversedFilteringCovarianceScaling =
1190         kfOptions.reversedFilteringCovarianceScaling;
1191     kalmanActor.freeToBoundCorrection = kfOptions.freeToBoundCorrection;
1192     kalmanActor.calibrationContext = &kfOptions.calibrationContext.get();
1193     kalmanActor.extensions = kfOptions.extensions;
1194     kalmanActor.actorLogger = m_actorLogger.get();
1195 
1196     return fit_impl<start_parameters_t, PropagatorOptions, KalmanResult,
1197                     track_container_t>(sParameters, propagatorOptions,
1198                                        trackContainer);
1199   }
1200 
1201   /// Fit implementation of the forward filter, calls the
1202   /// the filter and smoother/reversed filter
1203   ///
1204   /// @tparam source_link_iterator_t Iterator type used to pass source links
1205   /// @tparam start_parameters_t Type of the initial parameters
1206   /// @tparam parameters_t Type of parameters used for local parameters
1207   /// @tparam track_container_t Type of the track container
1208   ///
1209   /// @param it Begin iterator for the fittable uncalibrated measurements
1210   /// @param end End iterator for the fittable uncalibrated measurements
1211   /// @param sParameters The initial track parameters
1212   /// @param kfOptions KalmanOptions steering the fit
1213   /// @param sSequence surface sequence used to initialize a DirectNavigator
1214   /// @param trackContainer Input track container storage to append into
1215   /// @note The input measurements are given in the form of @c SourceLinks.
1216   /// It's
1217   /// @c calibrator_t's job to turn them into calibrated measurements used in
1218   /// the fit.
1219   ///
1220   /// @return the output as an output track
1221   template <typename source_link_iterator_t, typename start_parameters_t,
1222             typename parameters_t = BoundTrackParameters,
1223             TrackContainerFrontend track_container_t>
1224   Result<typename track_container_t::TrackProxy> fit(
1225       source_link_iterator_t it, source_link_iterator_t end,
1226       const start_parameters_t& sParameters,
1227       const KalmanFitterOptions<traj_t>& kfOptions,
1228       const std::vector<const Surface*>& sSequence,
1229       track_container_t& trackContainer) const
1230     requires(isDirectNavigator)
1231   {
1232     // To be able to find measurements later, we put them into a map
1233     // We need to copy input SourceLinks anyway, so the map can own them.
1234     ACTS_VERBOSE("Preparing " << std::distance(it, end)
1235                               << " input measurements");
1236     std::map<GeometryIdentifier, SourceLink> inputMeasurements;
1237     for (; it != end; ++it) {
1238       SourceLink sl = *it;
1239       const Surface* surface = kfOptions.extensions.surfaceAccessor(sl);
1240       // @TODO: This can probably change over to surface pointers as keys
1241       auto geoId = surface->geometryId();
1242       inputMeasurements.emplace(geoId, std::move(sl));
1243     }
1244 
1245     // Create the ActorList
1246     using KalmanActor = Actor<parameters_t>;
1247 
1248     using KalmanResult = typename KalmanActor::result_type;
1249     using Actors = ActorList<KalmanActor>;
1250     using PropagatorOptions = typename propagator_t::template Options<Actors>;
1251 
1252     // Create relevant options for the propagation options
1253     PropagatorOptions propagatorOptions(kfOptions.geoContext,
1254                                         kfOptions.magFieldContext);
1255 
1256     // Set the trivial propagator options
1257     propagatorOptions.setPlainOptions(kfOptions.propagatorPlainOptions);
1258 
1259     // Catch the actor and set the measurements
1260     auto& kalmanActor = propagatorOptions.actorList.template get<KalmanActor>();
1261     kalmanActor.inputMeasurements = &inputMeasurements;
1262     kalmanActor.targetReached.surface = kfOptions.referenceSurface;
1263     kalmanActor.targetSurfaceStrategy = kfOptions.referenceSurfaceStrategy;
1264     kalmanActor.multipleScattering = kfOptions.multipleScattering;
1265     kalmanActor.energyLoss = kfOptions.energyLoss;
1266     kalmanActor.reversedFiltering = kfOptions.reversedFiltering;
1267     kalmanActor.reversedFilteringCovarianceScaling =
1268         kfOptions.reversedFilteringCovarianceScaling;
1269     kalmanActor.freeToBoundCorrection = kfOptions.freeToBoundCorrection;
1270     kalmanActor.calibrationContext = &kfOptions.calibrationContext.get();
1271     kalmanActor.extensions = kfOptions.extensions;
1272     kalmanActor.actorLogger = m_actorLogger.get();
1273 
1274     // Set the surface sequence
1275     propagatorOptions.navigation.surfaces = sSequence;
1276 
1277     return fit_impl<start_parameters_t, PropagatorOptions, KalmanResult,
1278                     track_container_t>(sParameters, propagatorOptions,
1279                                        trackContainer);
1280   }
1281 
1282  private:
1283   /// Common fit implementation
1284   ///
1285   /// @tparam start_parameters_t Type of the initial parameters
1286   /// @tparam actor_list_t Type of the actor list
1287   /// @tparam aborter_list_t Type of the abort list
1288   /// @tparam kalman_result_t Type of the KF result
1289   /// @tparam track_container_t Type of the track container
1290   ///
1291   /// @param sParameters The initial track parameters
1292   /// @param propagatorOptions The Propagator Options
1293   /// @param trackContainer Input track container storage to append into
1294   ///
1295   /// @return the output as an output track
1296   template <typename start_parameters_t, typename propagator_options_t,
1297             typename kalman_result_t, TrackContainerFrontend track_container_t>
1298   auto fit_impl(const start_parameters_t& sParameters,
1299                 const propagator_options_t& propagatorOptions,
1300                 track_container_t& trackContainer) const
1301       -> Result<typename track_container_t::TrackProxy> {
1302     auto propagatorState = m_propagator.makeState(propagatorOptions);
1303 
1304     auto propagatorInitResult =
1305         m_propagator.initialize(propagatorState, sParameters);
1306     if (!propagatorInitResult.ok()) {
1307       ACTS_ERROR("Propagation initialization failed: "
1308                  << propagatorInitResult.error());
1309       return propagatorInitResult.error();
1310     }
1311 
1312     auto& kalmanResult =
1313         propagatorState.template get<KalmanFitterResult<traj_t>>();
1314     kalmanResult.fittedStates = &trackContainer.trackStateContainer();
1315 
1316     // Run the fitter
1317     auto result = m_propagator.propagate(propagatorState);
1318 
1319     if (!result.ok()) {
1320       ACTS_ERROR("Propagation failed: " << result.error());
1321       return result.error();
1322     }
1323 
1324     /// It could happen that the fit ends in zero measurement states.
1325     /// The result gets meaningless so such case is regarded as fit failure.
1326     if (kalmanResult.result.ok() && !kalmanResult.measurementStates) {
1327       kalmanResult.result = Result<void>(KalmanFitterError::NoMeasurementFound);
1328     }
1329 
1330     if (!kalmanResult.result.ok()) {
1331       ACTS_ERROR("KalmanFilter failed: "
1332                  << kalmanResult.result.error() << ", "
1333                  << kalmanResult.result.error().message());
1334       return kalmanResult.result.error();
1335     }
1336 
1337     auto track = trackContainer.makeTrack();
1338     track.tipIndex() = kalmanResult.lastMeasurementIndex;
1339     if (kalmanResult.fittedParameters) {
1340       const auto& params = kalmanResult.fittedParameters.value();
1341       track.parameters() = params.parameters();
1342       track.covariance() = params.covariance().value();
1343       track.setReferenceSurface(params.referenceSurface().getSharedPtr());
1344     }
1345 
1346     calculateTrackQuantities(track);
1347 
1348     if (trackContainer.hasColumn(hashString("smoothed"))) {
1349       track.template component<bool, hashString("smoothed")>() =
1350           kalmanResult.smoothed;
1351     }
1352 
1353     if (trackContainer.hasColumn(hashString("reversed"))) {
1354       track.template component<bool, hashString("reversed")>() =
1355           kalmanResult.reversed;
1356     }
1357 
1358     // Return the converted Track
1359     return track;
1360   }
1361 };
1362 
1363 }  // namespace Acts