Back to home page

EIC code displayed by LXR

 
 

    


File indexing completed on 2025-12-23 09:14:21

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/Definitions/Common.hpp"
0012 #include "Acts/EventData/MultiTrajectory.hpp"
0013 #include "Acts/EventData/MultiTrajectoryHelpers.hpp"
0014 #include "Acts/EventData/TrackParameters.hpp"
0015 #include "Acts/EventData/TrackStatePropMask.hpp"
0016 #include "Acts/EventData/Types.hpp"
0017 #include "Acts/Geometry/GeometryContext.hpp"
0018 #include "Acts/MagneticField/MagneticFieldContext.hpp"
0019 #include "Acts/Propagator/ActorList.hpp"
0020 #include "Acts/Propagator/ConstrainedStep.hpp"
0021 #include "Acts/Propagator/PropagatorState.hpp"
0022 #include "Acts/Propagator/StandardAborters.hpp"
0023 #include "Acts/Propagator/detail/LoopProtection.hpp"
0024 #include "Acts/Propagator/detail/PointwiseMaterialInteraction.hpp"
0025 #include "Acts/TrackFinding/CombinatorialKalmanFilterError.hpp"
0026 #include "Acts/TrackFinding/CombinatorialKalmanFilterExtensions.hpp"
0027 #include "Acts/Utilities/CalibrationContext.hpp"
0028 #include "Acts/Utilities/Logger.hpp"
0029 #include "Acts/Utilities/Result.hpp"
0030 
0031 #include <functional>
0032 #include <limits>
0033 #include <memory>
0034 #include <type_traits>
0035 
0036 namespace Acts {
0037 
0038 /// Combined options for the combinatorial Kalman filter.
0039 ///
0040 /// @tparam source_link_iterator_t Type of the source link iterator
0041 /// @tparam track_container_t Type of the track container
0042 template <typename track_container_t>
0043 struct CombinatorialKalmanFilterOptions {
0044   /// Type alias for track state container backend
0045   using TrackStateContainerBackend =
0046       typename track_container_t::TrackStateContainerBackend;
0047   /// Type alias for track state proxy from the container
0048   using TrackStateProxy = typename track_container_t::TrackStateProxy;
0049 
0050   /// PropagatorOptions with context
0051   ///
0052   /// @param gctx The geometry context for this track finding/fitting
0053   /// @param mctx The magnetic context for this track finding/fitting
0054   /// @param cctx The calibration context for this track finding/fitting
0055   /// @param extensions_ The extension struct
0056   /// @param pOptions The plain propagator options
0057   /// @param mScattering Whether to include multiple scattering
0058   /// @param eLoss Whether to include energy loss
0059   CombinatorialKalmanFilterOptions(
0060       const GeometryContext& gctx, const MagneticFieldContext& mctx,
0061       std::reference_wrapper<const CalibrationContext> cctx,
0062       CombinatorialKalmanFilterExtensions<track_container_t> extensions_,
0063       const PropagatorPlainOptions& pOptions, bool mScattering = true,
0064       bool eLoss = true)
0065       : geoContext(gctx),
0066         magFieldContext(mctx),
0067         calibrationContext(cctx),
0068         extensions(extensions_),
0069         propagatorPlainOptions(pOptions),
0070         multipleScattering(mScattering),
0071         energyLoss(eLoss) {}
0072 
0073   /// Contexts are required and the options must not be default-constructible.
0074   CombinatorialKalmanFilterOptions() = delete;
0075 
0076   /// Context object for the geometry
0077   std::reference_wrapper<const GeometryContext> geoContext;
0078   /// Context object for the magnetic field
0079   std::reference_wrapper<const MagneticFieldContext> magFieldContext;
0080   /// context object for the calibration
0081   std::reference_wrapper<const CalibrationContext> calibrationContext;
0082 
0083   /// The filter extensions
0084   CombinatorialKalmanFilterExtensions<track_container_t> extensions;
0085 
0086   /// The trivial propagator options
0087   PropagatorPlainOptions propagatorPlainOptions;
0088 
0089   /// The target surface
0090   /// @note This is useful if the filtering should be terminated at a
0091   ///       certain surface
0092   const Surface* targetSurface = nullptr;
0093 
0094   /// Whether to consider multiple scattering.
0095   bool multipleScattering = true;
0096 
0097   /// Whether to consider energy loss.
0098   bool energyLoss = true;
0099 
0100   /// Skip the pre propagation call. This effectively skips the first surface
0101   /// @note This is useful if the first surface should not be considered in a second reverse pass
0102   bool skipPrePropagationUpdate = false;
0103 };
0104 
0105 template <typename track_container_t>
0106 struct CombinatorialKalmanFilterResult {
0107   using TrackStateContainerBackend =
0108       typename track_container_t::TrackStateContainerBackend;
0109   using TrackProxy = typename track_container_t::TrackProxy;
0110   using TrackStateProxy = typename track_container_t::TrackStateProxy;
0111 
0112   /// The track container to store the found tracks
0113   track_container_t* tracks{nullptr};
0114 
0115   /// Fitted states that the actor has handled.
0116   TrackStateContainerBackend* trackStates{nullptr};
0117 
0118   /// Indices into `tracks` which mark active branches
0119   std::vector<TrackProxy> activeBranches;
0120 
0121   /// Indices into `tracks` which mark active branches
0122   std::vector<TrackProxy> collectedTracks;
0123 
0124   /// Track state candidates buffer which can be used by the track state creator
0125   std::vector<TrackStateProxy> trackStateCandidates;
0126 
0127   /// Indicator if track finding has been done
0128   bool finished = false;
0129 
0130   /// Last encountered error
0131   Result<void> lastError{Result<void>::success()};
0132 
0133   /// Path limit aborter
0134   PathLimitReached pathLimitReached;
0135 };
0136 
0137 /// Combinatorial Kalman filter to find tracks.
0138 ///
0139 /// @tparam propagator_t Type of the propagator
0140 ///
0141 /// The CombinatorialKalmanFilter contains an Actor and a Sequencer sub-class.
0142 /// The Sequencer has to be part of the Navigator of the Propagator in order to
0143 /// initialize and provide the measurement surfaces.
0144 ///
0145 /// The Actor is part of the Propagation call and does the Kalman update.
0146 /// Updater and Calibrator are given to the Actor for further use:
0147 /// - The Updater is the implemented kalman updater formalism, it
0148 ///   runs via a visitor pattern through the measurements.
0149 ///
0150 /// Measurements are not required to be ordered for the
0151 /// CombinatorialKalmanFilter, measurement ordering needs to be figured out by
0152 /// the navigation of the propagator.
0153 ///
0154 /// The void components are provided mainly for unit testing.
0155 ///
0156 template <typename propagator_t, typename track_container_t>
0157 class CombinatorialKalmanFilter {
0158  public:
0159   /// Default constructor is deleted
0160   CombinatorialKalmanFilter() = delete;
0161 
0162   /// Constructor with propagator and logging level
0163   /// @param pPropagator The propagator used for the track finding
0164   /// @param _logger The logger for messages
0165   explicit CombinatorialKalmanFilter(propagator_t pPropagator,
0166                                      std::unique_ptr<const Logger> _logger =
0167                                          getDefaultLogger("CKF", Logging::INFO))
0168       : m_propagator(std::move(pPropagator)),
0169         m_logger(std::move(_logger)),
0170         m_actorLogger{m_logger->cloneWithSuffix("Actor")},
0171         m_updaterLogger{m_logger->cloneWithSuffix("Updater")} {}
0172 
0173  private:
0174   using BoundState = std::tuple<BoundTrackParameters, BoundMatrix, double>;
0175   using TrackStateContainerBackend =
0176       typename track_container_t::TrackStateContainerBackend;
0177   using TrackProxy = typename track_container_t::TrackProxy;
0178   using TrackStateProxy = typename track_container_t::TrackStateProxy;
0179 
0180   /// The propagator for the transport and material update
0181   propagator_t m_propagator;
0182 
0183   std::unique_ptr<const Logger> m_logger;
0184   std::shared_ptr<const Logger> m_actorLogger;
0185   std::shared_ptr<const Logger> m_updaterLogger;
0186 
0187   const Logger& logger() const { return *m_logger; }
0188 
0189   /// @brief Propagator Actor plugin for the CombinatorialKalmanFilter
0190   ///
0191   /// The CombinatorialKalmanFilter Actor does not rely on the measurements to
0192   /// be sorted along the track.
0193   class Actor {
0194    public:
0195     using BoundState = std::tuple<BoundTrackParameters, BoundMatrix, double>;
0196     /// Broadcast the result_type
0197     using result_type = CombinatorialKalmanFilterResult<track_container_t>;
0198 
0199     using BranchStopperResult = CombinatorialKalmanFilterBranchStopperResult;
0200 
0201     /// The target surface aborter
0202     SurfaceReached targetReached{std::numeric_limits<double>::lowest()};
0203 
0204     /// Whether to consider multiple scattering.
0205     bool multipleScattering = true;
0206 
0207     /// Whether to consider energy loss.
0208     bool energyLoss = true;
0209 
0210     /// Skip the pre propagation call. This effectively skips the first surface
0211     bool skipPrePropagationUpdate = false;
0212 
0213     /// Calibration context for the finding run
0214     const CalibrationContext* calibrationContextPtr{nullptr};
0215 
0216     CombinatorialKalmanFilterExtensions<track_container_t> extensions;
0217 
0218     /// End of world aborter
0219     EndOfWorldReached endOfWorldReached;
0220 
0221     /// Volume constraint aborter
0222     VolumeConstraintAborter volumeConstraintAborter;
0223 
0224     /// Actor logger instance
0225     const Logger* actorLogger{nullptr};
0226     /// Updater logger instance
0227     const Logger* updaterLogger{nullptr};
0228 
0229     const Logger& logger() const { return *actorLogger; }
0230 
0231     /// @brief CombinatorialKalmanFilter actor operation
0232     ///
0233     /// @tparam propagator_state_t Type of the Propagator state
0234     /// @tparam stepper_t Type of the stepper
0235     ///
0236     /// @param state is the mutable propagator state object
0237     /// @param stepper is the stepper in use
0238     /// @param navigator is the navigator in use
0239     /// @param result is the mutable result state object
0240     template <typename propagator_state_t, typename stepper_t,
0241               typename navigator_t>
0242     void act(propagator_state_t& state, const stepper_t& stepper,
0243              const navigator_t& navigator, result_type& result,
0244              const Logger& /*logger*/) const {
0245       ACTS_VERBOSE("CKF Actor called");
0246 
0247       assert(result.trackStates && "No MultiTrajectory set");
0248 
0249       if (state.stage == PropagatorStage::prePropagation &&
0250           skipPrePropagationUpdate) {
0251         ACTS_VERBOSE("Skip pre-propagation update (first surface)");
0252         return;
0253       }
0254       if (state.stage == PropagatorStage::postPropagation) {
0255         ACTS_VERBOSE("Skip post-propagation action");
0256         return;
0257       }
0258 
0259       ACTS_VERBOSE("CombinatorialKalmanFilter step");
0260 
0261       assert(!result.activeBranches.empty() && "No active branches");
0262       assert(!result.finished && "Should never reach this when finished");
0263       assert(result.lastError.ok() &&
0264              "Should never reach this when `lastError` is set");
0265 
0266       // Initialize path limit reached aborter
0267       if (result.pathLimitReached.internalLimit ==
0268           std::numeric_limits<double>::max()) {
0269         detail::setupLoopProtection(state, stepper, result.pathLimitReached,
0270                                     true, logger());
0271       }
0272 
0273       // Update:
0274       // - Waiting for a current surface
0275       if (const Surface* surface = navigator.currentSurface(state.navigation);
0276           surface != nullptr) {
0277         // There are three scenarios:
0278         // 1) The surface is in the measurement map
0279         // -> Select source links
0280         // -> Perform the kalman update for selected non-outlier source links
0281         // -> Add track states in multitrajectory. Multiple states mean branch
0282         // splitting.
0283         // -> Call branch stopper to justify each branch
0284         // -> If there is non-outlier state, update stepper information
0285         // 2) The surface is not in the measurement map but with material or is
0286         // an active surface
0287         // -> Add a hole or passive material state in multitrajectory
0288         // -> Call branch stopper to justify the branch
0289         // 3) The surface is neither in the measurement map nor with material
0290         // -> Do nothing
0291         ACTS_VERBOSE("Perform filter step");
0292         auto res = filter(surface, state, stepper, navigator, result);
0293         if (!res.ok()) {
0294           ACTS_ERROR("Error in filter: " << res.error().message());
0295           result.lastError = res.error();
0296         }
0297 
0298         if (!result.lastError.ok() || result.finished) {
0299           ACTS_VERBOSE("CKF Actor returns after filter step");
0300           return;
0301         }
0302       }
0303 
0304       assert(!result.activeBranches.empty() && "No active branches");
0305 
0306       const bool isEndOfWorldReached =
0307           endOfWorldReached.checkAbort(state, stepper, navigator, logger());
0308       const bool isVolumeConstraintReached = volumeConstraintAborter.checkAbort(
0309           state, stepper, navigator, logger());
0310       const bool isPathLimitReached = result.pathLimitReached.checkAbort(
0311           state, stepper, navigator, logger());
0312       const bool isTargetReached =
0313           targetReached.checkAbort(state, stepper, navigator, logger());
0314       if (isEndOfWorldReached || isVolumeConstraintReached ||
0315           isPathLimitReached || isTargetReached) {
0316         if (isEndOfWorldReached) {
0317           ACTS_VERBOSE("End of world reached");
0318         } else if (isVolumeConstraintReached) {
0319           ACTS_VERBOSE("Volume constraint reached");
0320         } else if (isPathLimitReached) {
0321           ACTS_VERBOSE("Path limit reached");
0322         } else if (isTargetReached) {
0323           ACTS_VERBOSE("Target surface reached");
0324 
0325           // Bind the parameter to the target surface
0326           auto res = stepper.boundState(state.stepping, *targetReached.surface);
0327           if (!res.ok()) {
0328             ACTS_ERROR("Error while acquiring bound state for target surface: "
0329                        << res.error() << " " << res.error().message());
0330             result.lastError = res.error();
0331           } else {
0332             const auto& [boundParams, jacobian, pathLength] = *res;
0333             auto currentBranch = result.activeBranches.back();
0334             // Assign the fitted parameters
0335             currentBranch.parameters() = boundParams.parameters();
0336             currentBranch.covariance() = *boundParams.covariance();
0337             currentBranch.setReferenceSurface(
0338                 boundParams.referenceSurface().getSharedPtr());
0339           }
0340 
0341           stepper.releaseStepSize(state.stepping,
0342                                   ConstrainedStep::Type::Navigator);
0343         }
0344 
0345         // Record the active branch and remove it from the list
0346         storeLastActiveBranch(result);
0347         result.activeBranches.pop_back();
0348 
0349         // Reset propagation state to track state at next active branch
0350         reset(state, stepper, navigator, result);
0351       }
0352     }
0353 
0354     template <typename propagator_state_t, typename stepper_t,
0355               typename navigator_t>
0356     bool checkAbort(propagator_state_t& /*state*/, const stepper_t& /*stepper*/,
0357                     const navigator_t& /*navigator*/, const result_type& result,
0358                     const Logger& /*logger*/) const {
0359       return !result.lastError.ok() || result.finished;
0360     }
0361 
0362     /// @brief CombinatorialKalmanFilter actor operation: reset propagation
0363     ///
0364     /// @tparam propagator_state_t Type of Propagator state
0365     /// @tparam stepper_t Type of the stepper
0366     /// @tparam navigator_t Type of the navigator
0367     ///
0368     /// @param state is the mutable propagator state object
0369     /// @param stepper is the stepper in use
0370     /// @param navigator is the navigator in use
0371     /// @param result is the mutable result state object
0372     template <typename propagator_state_t, typename stepper_t,
0373               typename navigator_t>
0374     void reset(propagator_state_t& state, const stepper_t& stepper,
0375                const navigator_t& navigator, result_type& result) const {
0376       if (result.activeBranches.empty()) {
0377         ACTS_VERBOSE("Stop CKF with " << result.collectedTracks.size()
0378                                       << " found tracks");
0379         result.finished = true;
0380 
0381         return;
0382       }
0383 
0384       auto currentBranch = result.activeBranches.back();
0385       auto currentState = currentBranch.outermostTrackState();
0386 
0387       ACTS_VERBOSE("Propagation jumps to branch with tip = "
0388                    << currentBranch.tipIndex());
0389 
0390       // Reset the stepping state
0391       stepper.initialize(state.stepping, currentState.filtered(),
0392                          currentState.filteredCovariance(),
0393                          stepper.particleHypothesis(state.stepping),
0394                          currentState.referenceSurface());
0395 
0396       // Reset the navigation state
0397       // Set targetSurface to nullptr for forward filtering
0398       state.navigation.options.startSurface = &currentState.referenceSurface();
0399       state.navigation.options.targetSurface = nullptr;
0400       auto navInitRes = navigator.initialize(
0401           state.navigation, stepper.position(state.stepping),
0402           stepper.direction(state.stepping), state.options.direction);
0403       if (!navInitRes.ok()) {
0404         ACTS_ERROR("Navigation initialization failed: " << navInitRes.error());
0405         result.lastError = navInitRes.error();
0406       }
0407 
0408       // No Kalman filtering for the starting surface, but still need
0409       // to consider the material effects here
0410       materialInteractor(navigator.currentSurface(state.navigation), state,
0411                          stepper, navigator, MaterialUpdateStage::PostUpdate);
0412 
0413       // Set path limit based on loop protection
0414       detail::setupLoopProtection(state, stepper, result.pathLimitReached, true,
0415                                   logger());
0416 
0417       // Set path limit based on target surface
0418       targetReached.checkAbort(state, stepper, navigator, logger());
0419     }
0420 
0421     /// @brief CombinatorialKalmanFilter actor operation:
0422     /// - filtering for all measurement(s) on surface
0423     /// - store selected track states in multiTrajectory
0424     /// - update propagator state to the (last) selected track state
0425     ///
0426     /// @tparam propagator_state_t Type of the Propagator state
0427     /// @tparam stepper_t Type of the stepper
0428     /// @tparam navigator_t Type of the navigator
0429     ///
0430     /// @param surface The surface where the update happens
0431     /// @param state The mutable propagator state object
0432     /// @param stepper The stepper in use
0433     /// @param navigator The navigator in use
0434     /// @param result The mutable result state object
0435     template <typename propagator_state_t, typename stepper_t,
0436               typename navigator_t>
0437     Result<void> filter(const Surface* surface, propagator_state_t& state,
0438                         const stepper_t& stepper, const navigator_t& navigator,
0439                         result_type& result) const {
0440       using PM = TrackStatePropMask;
0441 
0442       bool isSensitive = surface->associatedDetectorElement() != nullptr;
0443       bool hasMaterial = surface->surfaceMaterial() != nullptr;
0444       bool isMaterialOnly = hasMaterial && !isSensitive;
0445       bool expectMeasurements = isSensitive;
0446 
0447       if (isSensitive) {
0448         ACTS_VERBOSE("Measurement surface " << surface->geometryId()
0449                                             << " detected.");
0450       } else if (isMaterialOnly) {
0451         ACTS_VERBOSE("Material surface " << surface->geometryId()
0452                                          << " detected.");
0453       } else {
0454         ACTS_VERBOSE("Passive surface " << surface->geometryId()
0455                                         << " detected.");
0456         return Result<void>::success();
0457       }
0458 
0459       // Transport the covariance to the surface
0460       if (isMaterialOnly) {
0461         stepper.transportCovarianceToCurvilinear(state.stepping);
0462       } else {
0463         stepper.transportCovarianceToBound(state.stepping, *surface);
0464       }
0465 
0466       // Update state and stepper with pre material effects
0467       materialInteractor(surface, state, stepper, navigator,
0468                          MaterialUpdateStage::PreUpdate);
0469 
0470       // Bind the transported state to the current surface
0471       auto boundStateRes = stepper.boundState(state.stepping, *surface, false);
0472       if (!boundStateRes.ok()) {
0473         return boundStateRes.error();
0474       }
0475       auto& boundState = *boundStateRes;
0476       auto& [boundParams, jacobian, pathLength] = boundState;
0477       boundParams.covariance() = state.stepping.cov;
0478 
0479       auto currentBranch = result.activeBranches.back();
0480       TrackIndexType prevTip = currentBranch.tipIndex();
0481 
0482       using TrackStatesResult = Result<CkfTypes::BranchVector<TrackIndexType>>;
0483       TrackStatesResult tsRes = TrackStatesResult::success({});
0484       if (isSensitive) {
0485         // extend trajectory with measurements associated to the current surface
0486         // which may create extra trajectory branches if more than one
0487         // measurement is selected.
0488         tsRes = extensions.createTrackStates(
0489             state.geoContext, *calibrationContextPtr, *surface, boundState,
0490             prevTip, result.trackStateCandidates, *result.trackStates,
0491             logger());
0492       }
0493 
0494       if (tsRes.ok() && !(*tsRes).empty()) {
0495         const CkfTypes::BranchVector<TrackIndexType>& newTrackStateList =
0496             *tsRes;
0497         Result<unsigned int> procRes =
0498             processNewTrackStates(state.geoContext, newTrackStateList, result);
0499         if (!procRes.ok()) {
0500           ACTS_ERROR("Processing of selected track states failed: "
0501                      << procRes.error().message());
0502           return procRes.error();
0503         }
0504         unsigned int nBranchesOnSurface = *procRes;
0505 
0506         if (nBranchesOnSurface == 0) {
0507           ACTS_VERBOSE("All branches on surface " << surface->geometryId()
0508                                                   << " have been stopped");
0509 
0510           reset(state, stepper, navigator, result);
0511 
0512           return Result<void>::success();
0513         }
0514 
0515         // `currentBranch` is invalidated after `processNewTrackStates`
0516         currentBranch = result.activeBranches.back();
0517         prevTip = currentBranch.tipIndex();
0518       } else {
0519         if (!tsRes.ok()) {
0520           if (static_cast<CombinatorialKalmanFilterError>(
0521                   tsRes.error().value()) ==
0522               CombinatorialKalmanFilterError::NoMeasurementExpected) {
0523             // recoverable error returned by track state creator
0524             expectMeasurements = false;
0525           } else {
0526             ACTS_ERROR("Track state creation failed on surface "
0527                        << surface->geometryId() << ": " << tsRes.error());
0528             return tsRes.error();
0529           }
0530         }
0531 
0532         if (expectMeasurements) {
0533           ACTS_VERBOSE("Detected hole after measurement selection on surface "
0534                        << surface->geometryId());
0535         }
0536 
0537         auto stateMask = PM::Predicted | PM::Jacobian;
0538 
0539         // Add a hole or material track state to the multitrajectory
0540         TrackIndexType currentTip =
0541             addNonSourcelinkState(stateMask, boundState, result, isSensitive,
0542                                   expectMeasurements, prevTip);
0543         currentBranch.tipIndex() = currentTip;
0544         auto currentState = currentBranch.outermostTrackState();
0545         if (expectMeasurements) {
0546           currentBranch.nHoles()++;
0547         }
0548 
0549         BranchStopperResult branchStopperResult =
0550             extensions.branchStopper(currentBranch, currentState);
0551 
0552         // Check the branch
0553         if (branchStopperResult == BranchStopperResult::Continue) {
0554           // Remembered the active branch and its state
0555         } else {
0556           // No branch on this surface
0557           if (branchStopperResult == BranchStopperResult::StopAndKeep) {
0558             storeLastActiveBranch(result);
0559           }
0560           // Remove the branch from list
0561           result.activeBranches.pop_back();
0562 
0563           // Branch on the surface has been stopped - reset
0564           ACTS_VERBOSE("Branch on surface " << surface->geometryId()
0565                                             << " has been stopped");
0566 
0567           reset(state, stepper, navigator, result);
0568 
0569           return Result<void>::success();
0570         }
0571       }
0572 
0573       auto currentState = currentBranch.outermostTrackState();
0574 
0575       if (currentState.typeFlags().test(TrackStateFlag::OutlierFlag)) {
0576         // We don't need to update the stepper given an outlier state
0577         ACTS_VERBOSE("Outlier state detected on surface "
0578                      << surface->geometryId());
0579       } else if (currentState.typeFlags().test(
0580                      TrackStateFlag::MeasurementFlag)) {
0581         // If there are measurement track states on this surface
0582         // Update stepping state using filtered parameters of last track
0583         // state on this surface
0584         stepper.update(state.stepping,
0585                        MultiTrajectoryHelpers::freeFiltered(
0586                            state.options.geoContext, currentState),
0587                        currentState.filtered(),
0588                        currentState.filteredCovariance(), *surface);
0589         ACTS_VERBOSE("Stepping state is updated with filtered parameter:");
0590         ACTS_VERBOSE("-> " << currentState.filtered().transpose()
0591                            << " of track state with tip = "
0592                            << currentState.index());
0593       }
0594 
0595       // Update state and stepper with post material effects
0596       materialInteractor(surface, state, stepper, navigator,
0597                          MaterialUpdateStage::PostUpdate);
0598 
0599       return Result<void>::success();
0600     }
0601 
0602     /// Process new, incompomplete track states and set the filtered state
0603     ///
0604     /// @note will process the given list of new states, run the updater
0605     ///     or share the predicted state for states flagged as outliers
0606     ///     and add them to the list of active branches
0607     ///
0608     /// @param gctx The geometry context for this track finding/fitting
0609     /// @param newTrackStateList index list of new track states
0610     /// @param result which contains among others the new states, and the list of active branches
0611     /// @return the number of newly added branches or an error
0612     Result<unsigned int> processNewTrackStates(
0613         const GeometryContext& gctx,
0614         const CkfTypes::BranchVector<TrackIndexType>& newTrackStateList,
0615         result_type& result) const {
0616       using PM = TrackStatePropMask;
0617 
0618       unsigned int nBranchesOnSurface = 0;
0619 
0620       auto rootBranch = result.activeBranches.back();
0621 
0622       // Build the new branches by forking the root branch. Reverse the order
0623       // to process the best candidate first
0624       CkfTypes::BranchVector<TrackProxy> newBranches;
0625       for (auto it = newTrackStateList.rbegin(); it != newTrackStateList.rend();
0626            ++it) {
0627         // Keep the root branch as the first branch, make a copy for the
0628         // others
0629         auto shallowCopy = [&] {
0630           auto sc = rootBranch.container().makeTrack();
0631           sc.copyFromShallow(rootBranch);
0632           return sc;
0633         };
0634         auto newBranch =
0635             (it == newTrackStateList.rbegin()) ? rootBranch : shallowCopy();
0636         newBranch.tipIndex() = *it;
0637         newBranches.push_back(newBranch);
0638       }
0639 
0640       // Remove the root branch
0641       result.activeBranches.pop_back();
0642 
0643       // Update and select from the new branches
0644       for (TrackProxy newBranch : newBranches) {
0645         auto trackState = newBranch.outermostTrackState();
0646         TrackStateType typeFlags = trackState.typeFlags();
0647 
0648         if (typeFlags.test(TrackStateFlag::OutlierFlag)) {
0649           // No Kalman update for outlier
0650           // Set the filtered parameter index to be the same with predicted
0651           // parameter
0652           trackState.shareFrom(PM::Predicted, PM::Filtered);
0653           // Increment number of outliers
0654           newBranch.nOutliers()++;
0655         } else if (typeFlags.test(TrackStateFlag::MeasurementFlag)) {
0656           // Kalman update
0657           auto updateRes = extensions.updater(gctx, trackState, *updaterLogger);
0658           if (!updateRes.ok()) {
0659             ACTS_ERROR("Update step failed: " << updateRes.error().message());
0660             return updateRes.error();
0661           }
0662           ACTS_VERBOSE("Appended measurement track state with tip = "
0663                        << newBranch.tipIndex());
0664           // Set the measurement flag
0665           typeFlags.set(TrackStateFlag::MeasurementFlag);
0666           // Increment number of measurements
0667           newBranch.nMeasurements()++;
0668           newBranch.nDoF() += trackState.calibratedSize();
0669           newBranch.chi2() += trackState.chi2();
0670         } else {
0671           ACTS_WARNING("Cannot handle this track state flags");
0672           continue;
0673         }
0674 
0675         result.activeBranches.push_back(newBranch);
0676 
0677         BranchStopperResult branchStopperResult =
0678             extensions.branchStopper(newBranch, trackState);
0679 
0680         // Check if need to stop this branch
0681         if (branchStopperResult == BranchStopperResult::Continue) {
0682           // Record the number of branches on surface
0683           nBranchesOnSurface++;
0684         } else {
0685           // Record the number of stopped branches
0686           if (branchStopperResult == BranchStopperResult::StopAndKeep) {
0687             storeLastActiveBranch(result);
0688           }
0689           // Remove the branch from list
0690           result.activeBranches.pop_back();
0691         }
0692       }
0693 
0694       return nBranchesOnSurface;
0695     }
0696 
0697     /// @brief CombinatorialKalmanFilter actor operation: add a hole or material track state
0698     ///
0699     /// @param stateMask The bitmask that instructs which components to allocate
0700     /// @param boundState The bound state on current surface
0701     /// @param result is the mutable result state object and which to leave invalid
0702     /// @param isSensitive The surface is sensitive or passive
0703     /// @param expectMeasurements True if measurements where expected for this surface
0704     /// @param prevTip The index of the previous state
0705     ///
0706     /// @return The tip of added state
0707     TrackIndexType addNonSourcelinkState(TrackStatePropMask stateMask,
0708                                          const BoundState& boundState,
0709                                          result_type& result, bool isSensitive,
0710                                          bool expectMeasurements,
0711                                          TrackIndexType prevTip) const {
0712       using PM = TrackStatePropMask;
0713 
0714       // Add a track state
0715       auto trackStateProxy =
0716           result.trackStates->makeTrackState(stateMask, prevTip);
0717       ACTS_VERBOSE("Create "
0718                    << (isSensitive
0719                            ? (expectMeasurements ? "Hole"
0720                                                  : "noMeasurementExpected")
0721                            : "Material")
0722                    << " output track state #" << trackStateProxy.index()
0723                    << " with mask: " << stateMask);
0724 
0725       const auto& [boundParams, jacobian, pathLength] = boundState;
0726       // Fill the track state
0727       trackStateProxy.predicted() = boundParams.parameters();
0728       trackStateProxy.predictedCovariance() = boundParams.covariance().value();
0729       trackStateProxy.jacobian() = jacobian;
0730       trackStateProxy.pathLength() = pathLength;
0731       // Set the surface
0732       trackStateProxy.setReferenceSurface(
0733           boundParams.referenceSurface().getSharedPtr());
0734 
0735       // Set the track state flags
0736       auto typeFlags = trackStateProxy.typeFlags();
0737       if (trackStateProxy.referenceSurface().surfaceMaterial() != nullptr) {
0738         typeFlags.set(TrackStateFlag::MaterialFlag);
0739       }
0740       typeFlags.set(TrackStateFlag::ParameterFlag);
0741       if (isSensitive) {
0742         typeFlags.set(expectMeasurements ? TrackStateFlag::HoleFlag
0743                                          : TrackStateFlag::NoExpectedHitFlag);
0744       }
0745 
0746       // Set the filtered parameter index to be the same with predicted
0747       // parameter
0748       trackStateProxy.shareFrom(PM::Predicted, PM::Filtered);
0749 
0750       return trackStateProxy.index();
0751     }
0752 
0753     /// @brief CombinatorialKalmanFilter actor operation: material interaction
0754     ///
0755     /// @tparam propagator_state_t is the type of Propagator state
0756     /// @tparam stepper_t Type of the stepper
0757     /// @tparam navigator_t Type of the navigator
0758     ///
0759     /// @param surface The surface where the material interaction happens
0760     /// @param state The mutable propagator state object
0761     /// @param stepper The stepper in use
0762     /// @param navigator The navigator in use
0763     /// @param updateStage The material update stage
0764     template <typename propagator_state_t, typename stepper_t,
0765               typename navigator_t>
0766     void materialInteractor(const Surface* surface, propagator_state_t& state,
0767                             const stepper_t& stepper,
0768                             const navigator_t& navigator,
0769                             const MaterialUpdateStage& updateStage) const {
0770       if (surface == nullptr) {
0771         return;
0772       }
0773 
0774       // Indicator if having material
0775       bool hasMaterial = false;
0776 
0777       if (surface->surfaceMaterial() != nullptr) {
0778         // Prepare relevant input particle properties
0779         detail::PointwiseMaterialInteraction interaction(surface, state,
0780                                                          stepper);
0781         // Evaluate the material properties
0782         if (interaction.evaluateMaterialSlab(state, navigator, updateStage)) {
0783           // Surface has material at this stage
0784           hasMaterial = true;
0785 
0786           // Evaluate the material effects
0787           interaction.evaluatePointwiseMaterialInteraction(multipleScattering,
0788                                                            energyLoss);
0789 
0790           // Screen out material effects info
0791           ACTS_VERBOSE("Material effects on surface: "
0792                        << surface->geometryId()
0793                        << " at update stage: " << updateStage << " are :");
0794           ACTS_VERBOSE("eLoss = "
0795                        << interaction.Eloss * interaction.navDir << ", "
0796                        << "variancePhi = " << interaction.variancePhi << ", "
0797                        << "varianceTheta = " << interaction.varianceTheta
0798                        << ", "
0799                        << "varianceQoverP = " << interaction.varianceQoverP);
0800 
0801           // Update the state and stepper with material effects
0802           interaction.updateState(state, stepper, addNoise);
0803         }
0804       }
0805 
0806       if (!hasMaterial) {
0807         // Screen out message
0808         ACTS_VERBOSE("No material effects on surface: " << surface->geometryId()
0809                                                         << " at update stage: "
0810                                                         << updateStage);
0811       }
0812     }
0813 
0814     void storeLastActiveBranch(result_type& result) const {
0815       auto currentBranch = result.activeBranches.back();
0816       TrackIndexType currentTip = currentBranch.tipIndex();
0817 
0818       ACTS_VERBOSE("Storing track "
0819                    << currentBranch.index() << " with tip index " << currentTip
0820                    << ". nMeasurements = " << currentBranch.nMeasurements()
0821                    << ", nOutliers = " << currentBranch.nOutliers()
0822                    << ", nHoles = " << currentBranch.nHoles());
0823 
0824       result.collectedTracks.push_back(currentBranch);
0825     }
0826   };
0827 
0828   /// Void path limit reached aborter to replace the default since the path
0829   /// limit is handled in the CKF actor internally.
0830   struct StubPathLimitReached {
0831     double internalLimit{};
0832 
0833     template <typename propagator_state_t, typename stepper_t,
0834               typename navigator_t>
0835     bool checkAbort(propagator_state_t& /*state*/, const stepper_t& /*stepper*/,
0836                     const navigator_t& /*navigator*/,
0837                     const Logger& /*logger*/) const {
0838       return false;
0839     }
0840   };
0841 
0842  public:
0843   /// Combinatorial Kalman Filter implementation, calls the Kalman filter
0844   ///
0845   /// @tparam start_parameters_t Type of the initial parameters
0846   /// @tparam parameters_t Type of parameters used for local parameters
0847   ///
0848   /// @param initialParameters The initial track parameters
0849   /// @param tfOptions CombinatorialKalmanFilterOptions steering the track
0850   ///                  finding
0851   /// @param trackContainer Track container in which to store the results
0852   /// @param rootBranch The track to be used as the root branch
0853   ///
0854   /// @note The input measurements are given in the form of @c SourceLinks.
0855   ///       It's @c calibrator_t's job to turn them into calibrated measurements
0856   ///       used in the track finding.
0857   ///
0858   /// @return a container of track finding result for all the initial track
0859   /// parameters
0860   template <typename start_parameters_t>
0861   auto findTracks(
0862       const start_parameters_t& initialParameters,
0863       const CombinatorialKalmanFilterOptions<track_container_t>& tfOptions,
0864       track_container_t& trackContainer,
0865       typename track_container_t::TrackProxy rootBranch) const
0866       -> Result<std::vector<
0867           typename std::decay_t<decltype(trackContainer)>::TrackProxy>> {
0868     // Create the ActorList
0869     using CombinatorialKalmanFilterActor = Actor;
0870     using Actors = ActorList<CombinatorialKalmanFilterActor>;
0871 
0872     // Create relevant options for the propagation options
0873     using PropagatorOptions = typename propagator_t::template Options<Actors>;
0874     PropagatorOptions propOptions(tfOptions.geoContext,
0875                                   tfOptions.magFieldContext);
0876 
0877     // Set the trivial propagator options
0878     propOptions.setPlainOptions(tfOptions.propagatorPlainOptions);
0879 
0880     // Catch the actor
0881     auto& combKalmanActor =
0882         propOptions.actorList.template get<CombinatorialKalmanFilterActor>();
0883     combKalmanActor.targetReached.surface = tfOptions.targetSurface;
0884     combKalmanActor.multipleScattering = tfOptions.multipleScattering;
0885     combKalmanActor.energyLoss = tfOptions.energyLoss;
0886     combKalmanActor.skipPrePropagationUpdate =
0887         tfOptions.skipPrePropagationUpdate;
0888     combKalmanActor.actorLogger = m_actorLogger.get();
0889     combKalmanActor.updaterLogger = m_updaterLogger.get();
0890     combKalmanActor.calibrationContextPtr = &tfOptions.calibrationContext.get();
0891 
0892     // copy delegates to calibrator, updater, branch stopper
0893     combKalmanActor.extensions = tfOptions.extensions;
0894 
0895     auto propState =
0896         m_propagator
0897             .template makeState<PropagatorOptions, StubPathLimitReached>(
0898                 propOptions);
0899 
0900     auto initResult = m_propagator.template initialize<
0901         decltype(propState), start_parameters_t, StubPathLimitReached>(
0902         propState, initialParameters);
0903     if (!initResult.ok()) {
0904       ACTS_ERROR("Propagation initialization failed: " << initResult.error());
0905       return initResult.error();
0906     }
0907 
0908     auto& r =
0909         propState
0910             .template get<CombinatorialKalmanFilterResult<track_container_t>>();
0911     r.tracks = &trackContainer;
0912     r.trackStates = &trackContainer.trackStateContainer();
0913 
0914     r.activeBranches.push_back(rootBranch);
0915 
0916     auto propagationResult = m_propagator.propagate(propState);
0917 
0918     auto result = m_propagator.makeResult(
0919         std::move(propState), propagationResult, propOptions, false);
0920 
0921     if (!result.ok()) {
0922       ACTS_ERROR("Propagation failed: " << result.error() << " "
0923                                         << result.error().message()
0924                                         << " with the initial parameters: \n"
0925                                         << initialParameters.parameters());
0926       return result.error();
0927     }
0928 
0929     auto& propRes = *result;
0930 
0931     // Get the result of the CombinatorialKalmanFilter
0932     auto combKalmanResult =
0933         std::move(propRes.template get<
0934                   CombinatorialKalmanFilterResult<track_container_t>>());
0935 
0936     Result<void> error = combKalmanResult.lastError;
0937     if (error.ok() && !combKalmanResult.finished) {
0938       error = Result<void>(
0939           CombinatorialKalmanFilterError::PropagationReachesMaxSteps);
0940     }
0941     if (!error.ok()) {
0942       ACTS_ERROR("CombinatorialKalmanFilter failed: "
0943                  << combKalmanResult.lastError.error() << " "
0944                  << combKalmanResult.lastError.error().message()
0945                  << " with the initial parameters: "
0946                  << initialParameters.parameters().transpose());
0947       return error.error();
0948     }
0949 
0950     return std::move(combKalmanResult.collectedTracks);
0951   }
0952 
0953   /// Combinatorial Kalman Filter implementation, calls the Kalman filter
0954   ///
0955   /// @tparam start_parameters_t Type of the initial parameters
0956   /// @tparam parameters_t Type of parameters used for local parameters
0957   ///
0958   /// @param initialParameters The initial track parameters
0959   /// @param tfOptions CombinatorialKalmanFilterOptions steering the track
0960   ///                  finding
0961   /// @param trackContainer Track container in which to store the results
0962   /// @note The input measurements are given in the form of @c SourceLinks.
0963   ///       It's @c calibrator_t's job to turn them into calibrated measurements
0964   ///       used in the track finding.
0965   ///
0966   /// @return a container of track finding result for all the initial track
0967   /// parameters
0968   template <typename start_parameters_t,
0969             typename parameters_t = BoundTrackParameters>
0970   auto findTracks(
0971       const start_parameters_t& initialParameters,
0972       const CombinatorialKalmanFilterOptions<track_container_t>& tfOptions,
0973       track_container_t& trackContainer) const
0974       -> Result<std::vector<
0975           typename std::decay_t<decltype(trackContainer)>::TrackProxy>> {
0976     auto rootBranch = trackContainer.makeTrack();
0977     return findTracks(initialParameters, tfOptions, trackContainer, rootBranch);
0978   }
0979 };
0980 
0981 }  // namespace Acts