Back to home page

EIC code displayed by LXR

 
 

    


Warning, file /include/Acts/TrackFinding/CombinatorialKalmanFilter.hpp was not indexed or was modified since last indexation (in which case cross-reference links may be missing, inaccurate or erroneous).

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