From 9017ba4a5a44a95aaca3ee93bf59d2804838e19a Mon Sep 17 00:00:00 2001 From: Fabian Klimpel Date: Thu, 2 Jul 2020 09:04:55 +0200 Subject: [PATCH] Remove TrackState (#289) The TrackState is not in use anymore and became superseded by the MultiTrajectory. --- .../Acts/EventData/MultiTrajectory.hpp | 33 +- .../Acts/EventData/MultiTrajectory.ipp | 84 ----- Core/include/Acts/EventData/TrackState.hpp | 181 --------- .../Acts/EventData/TrackStateSorters.hpp | 32 -- Core/include/Acts/Fitter/KalmanFitter.hpp | 2 - .../TrackFinder/CombinatorialKalmanFilter.hpp | 2 - Tests/UnitTests/Core/EventData/CMakeLists.txt | 1 - .../Core/EventData/MultiTrajectoryTests.cpp | 343 +++++++++--------- .../Core/EventData/TrackStateTests.cpp | 196 ---------- .../Core/Fitter/GainMatrixSmootherTests.cpp | 2 - .../Core/Fitter/GainMatrixUpdaterTests.cpp | 2 - .../Core/Fitter/KalmanFitterTests.cpp | 2 - .../Core/Visualization/EventDataViewBase.hpp | 1 - 13 files changed, 194 insertions(+), 687 deletions(-) delete mode 100644 Core/include/Acts/EventData/TrackState.hpp delete mode 100644 Core/include/Acts/EventData/TrackStateSorters.hpp delete mode 100644 Tests/UnitTests/Core/EventData/TrackStateTests.cpp diff --git a/Core/include/Acts/EventData/MultiTrajectory.hpp b/Core/include/Acts/EventData/MultiTrajectory.hpp index 7e65e9d7335..3c7d050c4da 100644 --- a/Core/include/Acts/EventData/MultiTrajectory.hpp +++ b/Core/include/Acts/EventData/MultiTrajectory.hpp @@ -15,7 +15,7 @@ #include -#include "Acts/EventData/TrackState.hpp" +#include "Acts/EventData/Measurement.hpp" #include "Acts/EventData/TrackStatePropMask.hpp" #include "Acts/Geometry/GeometryContext.hpp" #include "Acts/Utilities/ParameterDefinitions.hpp" @@ -23,6 +23,20 @@ namespace Acts { +/// @enum TrackStateFlag +/// +/// This enum describes the type of TrackState +enum TrackStateFlag { + MeasurementFlag = 0, + ParameterFlag = 1, + OutlierFlag = 2, + HoleFlag = 3, + MaterialFlag = 4, + NumTrackStateFlags = 5 +}; + +using TrackStateType = std::bitset; + // forward declarations template class MultiTrajectory; @@ -615,21 +629,6 @@ class MultiTrajectory { /// Create an empty trajectory. MultiTrajectory() = default; - /// Add a track state using information from a separate track state object. - /// - /// @tparam parameters_t The parameter type used for the trackstate - /// @param trackParameters at the local point - /// @param mask The bitmask that instructs which components to allocate and - /// which to leave invalid - /// @param iprevious index of the previous state, SIZE_MAX if first - /// @note The parameter type from @p parameters_t is not currently stored in - /// MultiTrajectory. - /// @return Index of the newly added track state - template - size_t addTrackState(const TrackState& ts, - TrackStatePropMask mask = TrackStatePropMask::All, - size_t iprevious = SIZE_MAX); - /// Add a track state without providing explicit information. Which components /// of the track state are initialized/allocated can be controlled via @p mask /// @param mask The bitmask that instructs which components to allocate and @@ -693,4 +692,4 @@ class MultiTrajectory { } // namespace Acts -#include "Acts/EventData/MultiTrajectory.ipp" +#include "Acts/EventData/MultiTrajectory.ipp" \ No newline at end of file diff --git a/Core/include/Acts/EventData/MultiTrajectory.ipp b/Core/include/Acts/EventData/MultiTrajectory.ipp index 1404583d1f3..3740cadf59c 100644 --- a/Core/include/Acts/EventData/MultiTrajectory.ipp +++ b/Core/include/Acts/EventData/MultiTrajectory.ipp @@ -13,7 +13,6 @@ #include -#include "Acts/EventData/TrackState.hpp" #include "Acts/Utilities/TypeTraits.hpp" namespace Acts { @@ -187,89 +186,6 @@ inline auto TrackStateProxy::calibratedCovariance() const } // namespace detail_lt -template -template -inline size_t MultiTrajectory::addTrackState( - const TrackState& ts, TrackStatePropMask mask, - size_t iprevious) { - using PropMask = TrackStatePropMask; - - // build a mask to allocate for the components in the trackstate - PropMask required = PropMask::None; - if (ts.parameter.predicted) { - required |= PropMask::Predicted; - } - - if (ts.parameter.filtered) { - required |= PropMask::Filtered; - } - - if (ts.parameter.smoothed) { - required |= PropMask::Smoothed; - } - - if (ts.parameter.jacobian) { - required |= PropMask::Jacobian; - } - - if (ts.measurement.uncalibrated) { - required |= PropMask::Uncalibrated; - } - - if (ts.measurement.calibrated) { - required |= PropMask::Calibrated; - } - - // use a TrackStateProxy to do the assignments - size_t index = addTrackState(mask | required, iprevious); - TrackStateProxy nts = getTrackState(index); - - // make shared ownership held by this multi trajectory - nts.setReferenceSurface(ts.referenceSurface().getSharedPtr()); - - // we don't need to check allocation, because we ORed with required components - // above - - if (ts.parameter.predicted) { - const auto& predicted = *ts.parameter.predicted; - nts.predicted() = predicted.parameters(); - nts.predictedCovariance() = *predicted.covariance(); - } - - if (ts.parameter.filtered) { - const auto& filtered = *ts.parameter.filtered; - nts.filtered() = filtered.parameters(); - nts.filteredCovariance() = *filtered.covariance(); - } - - if (ts.parameter.smoothed) { - const auto& smoothed = *ts.parameter.smoothed; - nts.smoothed() = smoothed.parameters(); - nts.smoothedCovariance() = *smoothed.covariance(); - } - - // store jacobian - if (ts.parameter.jacobian) { - nts.jacobian() = *ts.parameter.jacobian; - } - - // handle measurements - if (ts.measurement.uncalibrated) { - nts.uncalibrated() = *ts.measurement.uncalibrated; - } - - if (ts.measurement.calibrated) { - std::visit([&](const auto& m) { nts.setCalibrated(m); }, - *ts.measurement.calibrated); - } - - nts.chi2() = ts.parameter.chi2; - nts.pathLength() = ts.parameter.pathLength; - nts.typeFlags() = ts.type(); - - return nts.index(); -} - template inline size_t MultiTrajectory::addTrackState(TrackStatePropMask mask, size_t iprevious) { diff --git a/Core/include/Acts/EventData/TrackState.hpp b/Core/include/Acts/EventData/TrackState.hpp deleted file mode 100644 index ea587505506..00000000000 --- a/Core/include/Acts/EventData/TrackState.hpp +++ /dev/null @@ -1,181 +0,0 @@ -// This file is part of the Acts project. -// -// Copyright (C) 2018 CERN for the benefit of the Acts project -// -// This Source Code Form is subject to the terms of the Mozilla Public -// License, v. 2.0. If a copy of the MPL was not distributed with this -// file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#pragma once - -#include "Acts/EventData/Measurement.hpp" -#include "Acts/EventData/MeasurementHelpers.hpp" -#include "Acts/EventData/SourceLinkConcept.hpp" -#include "Acts/Utilities/ParameterDefinitions.hpp" - -#include - -namespace Acts { - -/// @enum TrackStateFlag -/// -/// This enum describes the type of TrackState -enum TrackStateFlag { - MeasurementFlag = 0, - ParameterFlag = 1, - OutlierFlag = 2, - HoleFlag = 3, - MaterialFlag = 4, - NumTrackStateFlags = 5 -}; - -using TrackStateType = std::bitset; - -class Surface; - -/// @class TrackState -/// -/// @brief Templated class to hold the track information -/// on a surface along the trajectory -/// -/// @tparam source_link_t Type of the source link -/// @tparam parameters_t Type of the parameters on the surface -/// -/// @note the Surface is only stored as a pointer, i.e. it is -/// assumed the surface lives longer than the TrackState -template -class TrackState { - static_assert(SourceLinkConcept, - "Source link does not fulfill SourceLinkConcept"); - - public: - using SourceLink = source_link_t; - using Parameters = parameters_t; - using Jacobian = typename Parameters::CovMatrix_t; - - /// Constructor from (uncalibrated) measurement - /// - /// @param m The measurement object - TrackState(SourceLink m) : m_surface(&m.referenceSurface()) { - measurement.uncalibrated = std::move(m); - m_typeFlags.set(MeasurementFlag); - } - - /// Constructor from parameters - /// - /// @tparam parameters_t Type of the predicted parameters - /// @param p The parameters object - TrackState(parameters_t p) { - m_surface = &p.referenceSurface(); - parameter.predicted = std::move(p); - m_typeFlags.set(ParameterFlag); - } - - /// Virtual destructor - virtual ~TrackState() = default; - - /// Copy constructor - /// - /// @param rhs is the source TrackState - TrackState(const TrackState& rhs) - : parameter(rhs.parameter), - measurement(rhs.measurement), - m_surface(rhs.m_surface), - m_typeFlags(rhs.m_typeFlags) {} - - /// Copy move constructor - /// - /// @param rhs is the source TrackState - TrackState(TrackState&& rhs) - : parameter(std::move(rhs.parameter)), - measurement(std::move(rhs.measurement)), - m_surface(std::move(rhs.m_surface)), - m_typeFlags(std::move(rhs.m_typeFlags)) {} - - /// Assignment operator - /// - /// @param rhs is the source TrackState - TrackState& operator=(const TrackState& rhs) { - parameter = rhs.parameter; - measurement = rhs.measurement; - m_surface = rhs.m_surface; - m_typeFlags = rhs.m_typeFlags; - return (*this); - } - - /// Assignment move operator - /// - /// @param rhs is the source TrackState - TrackState& operator=(TrackState&& rhs) { - parameter = std::move(rhs.parameter); - measurement = std::move(rhs.measurement); - m_surface = std::move(rhs.m_surface); - m_typeFlags = std::move(rhs.m_typeFlags); - return (*this); - } - - /// @brief return method for the surface - const Surface& referenceSurface() const { return (*m_surface); } - - /// @brief set the type flag - void setType(const TrackStateFlag& flag, bool status = true) { - m_typeFlags.set(flag, status); - } - - /// @brief test if the tracks state is flagged as a given type - bool isType(const TrackStateFlag& flag) const { - assert(flag < NumTrackStateFlags); - return m_typeFlags.test(flag); - } - - /// @brief return method for the type flags - TrackStateType type() const { return m_typeFlags; } - - /// @brief number of Measured parameters, forwarded - /// @note This only returns a value if there is a calibrated measurement - /// set. If not, this returns std::nullopt - /// - /// @return number of measured parameters, or std::nullopt - std::optional size() { - if (this->measurement.calibrated) { - return MeasurementHelpers::getSize(*this->measurement.calibrated); - } - return std::nullopt; - } - - /// The parameter part - /// This is all the information that concerns the - /// the track parameterisation and the jacobian - /// It is enough to to run the track smoothing - struct { - /// The predicted state - std::optional predicted{std::nullopt}; - /// The filtered state - std::optional filtered{std::nullopt}; - /// The smoothed state - std::optional smoothed{std::nullopt}; - /// The transport jacobian matrix - std::optional jacobian{std::nullopt}; - /// The path length along the track - will help sorting - double pathLength = 0.; - /// chisquare - double chi2 = 0; - } parameter; - - /// @brief Nested measurement part - /// This is the uncalibrated and calibrated measurement - /// (in case the latter is different) - struct { - /// The optional (uncalibrated) measurement - std::optional uncalibrated{std::nullopt}; - /// The optional calibrabed measurement - std::optional> calibrated{std::nullopt}; - } measurement; - - private: - /// The surface of this TrackState - const Surface* m_surface = nullptr; - /// The type flag of this TrackState - TrackStateType m_typeFlags; -}; -} // namespace Acts diff --git a/Core/include/Acts/EventData/TrackStateSorters.hpp b/Core/include/Acts/EventData/TrackStateSorters.hpp deleted file mode 100644 index db3956b40f9..00000000000 --- a/Core/include/Acts/EventData/TrackStateSorters.hpp +++ /dev/null @@ -1,32 +0,0 @@ -// This file is part of the Acts project. -// -// Copyright (C) 2016-2018 CERN for the benefit of the Acts project -// -// This Source Code Form is subject to the terms of the Mozilla Public -// License, v. 2.0. If a copy of the MPL was not distributed with this -// file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#pragma once - -namespace Acts { -/** - * Struct that sorts trackstates using their path lengths. - * This can be used as a sorter in STL functions. - */ -struct TrackStatePathLengthSorter { - public: - /** - * The sorting operator - * @tparam identifier_t Identifier of the track state - * @tparam parameters_t The concrete parameters type - * @param lhs First track state - * @param rhs Second trackstate - * @return bool - */ - template - bool operator()(const TrackState& lhs, - const TrackState& rhs) { - return lhs.parameter.pathLength < rhs.parameter.pathLength; - } -}; -} // namespace Acts diff --git a/Core/include/Acts/Fitter/KalmanFitter.hpp b/Core/include/Acts/Fitter/KalmanFitter.hpp index 392d6b46d83..7c17b73ada8 100644 --- a/Core/include/Acts/Fitter/KalmanFitter.hpp +++ b/Core/include/Acts/Fitter/KalmanFitter.hpp @@ -12,8 +12,6 @@ #include "Acts/EventData/MeasurementHelpers.hpp" #include "Acts/EventData/MultiTrajectory.hpp" #include "Acts/EventData/TrackParameters.hpp" -#include "Acts/EventData/TrackState.hpp" -#include "Acts/EventData/TrackStateSorters.hpp" #include "Acts/Fitter/KalmanFitterError.hpp" #include "Acts/Fitter/detail/VoidKalmanComponents.hpp" #include "Acts/Geometry/GeometryContext.hpp" diff --git a/Core/include/Acts/TrackFinder/CombinatorialKalmanFilter.hpp b/Core/include/Acts/TrackFinder/CombinatorialKalmanFilter.hpp index 3759560070b..49189c7511d 100644 --- a/Core/include/Acts/TrackFinder/CombinatorialKalmanFilter.hpp +++ b/Core/include/Acts/TrackFinder/CombinatorialKalmanFilter.hpp @@ -12,9 +12,7 @@ #include "Acts/EventData/MeasurementHelpers.hpp" #include "Acts/EventData/MultiTrajectory.hpp" #include "Acts/EventData/TrackParameters.hpp" -#include "Acts/EventData/TrackState.hpp" #include "Acts/EventData/TrackStatePropMask.hpp" -#include "Acts/EventData/TrackStateSorters.hpp" #include "Acts/Fitter/detail/VoidKalmanComponents.hpp" #include "Acts/Geometry/GeometryContext.hpp" #include "Acts/MagneticField/MagneticFieldContext.hpp" diff --git a/Tests/UnitTests/Core/EventData/CMakeLists.txt b/Tests/UnitTests/Core/EventData/CMakeLists.txt index 31b94fc80f1..d103fbd5d87 100644 --- a/Tests/UnitTests/Core/EventData/CMakeLists.txt +++ b/Tests/UnitTests/Core/EventData/CMakeLists.txt @@ -6,4 +6,3 @@ add_unittest(MeasurementHelpers MeasurementHelpersTests.cpp) add_unittest(Measurement MeasurementTests.cpp) add_unittest(MultiTrajectory MultiTrajectoryTests.cpp) add_unittest(ParameterSet ParameterSetTests.cpp) -add_unittest(TrackState TrackStateTests.cpp) \ No newline at end of file diff --git a/Tests/UnitTests/Core/EventData/MultiTrajectoryTests.cpp b/Tests/UnitTests/Core/EventData/MultiTrajectoryTests.cpp index feb452c6953..4d7ea7ddb79 100644 --- a/Tests/UnitTests/Core/EventData/MultiTrajectoryTests.cpp +++ b/Tests/UnitTests/Core/EventData/MultiTrajectoryTests.cpp @@ -1,6 +1,6 @@ // This file is part of the Acts project. // -// Copyright (C) 2019 CERN for the benefit of the Acts project +// Copyright (C) 2019-2020 CERN for the benefit of the Acts project // // This Source Code Form is subject to the terms of the Mozilla Public // License, v. 2.0. If a copy of the MPL was not distributed with this @@ -12,7 +12,6 @@ #include "Acts/EventData/MeasurementHelpers.hpp" #include "Acts/EventData/MultiTrajectory.hpp" #include "Acts/EventData/TrackParameters.hpp" -#include "Acts/EventData/TrackState.hpp" #include "Acts/Geometry/GeometryContext.hpp" #include "Acts/Tests/CommonHelpers/FloatComparisons.hpp" #include "Acts/Utilities/TypeTraits.hpp" @@ -40,77 +39,94 @@ CurvilinearParameters make_params() { return {cov, Vector3D(0, 0, 1), Vector3D(100, 1000, 400), -1, 0}; } -TrackState make_rand_trackstate() { - return {make_params()}; -} - using ParVec_t = BoundParameters::ParVector_t; using CovMat_t = BoundParameters::CovMatrix_t; -// std::pair, -// std::unique_ptr>> -auto make_trackstate(size_t dim = 3) { +struct TestTrackState { + SourceLink sourceLink; + std::optional> meas3d; + std::optional> meas2d; + std::optional predicted; + std::optional filtered; + std::optional smoothed; + CovMat_t jacobian; + double chi2; + double pathLength; +}; + +/// @brief Fills a @c TrackStateProxy object +/// +/// @tparam track_state_t Type of the TrackStateProxy +/// +/// @param [in, out] ts TrackStateProxy which is filled +/// @param [in] mask Specifies which components are filled +/// @param [in] dim Dimension of the measurement +/// +/// @return Tuple containing a @c TestTrackState and the @c FittableMeasurement +/// that were generated in this function +template +auto fillTrackState(track_state_t& ts, TrackStatePropMask mask, + size_t dim = 3) { auto plane = Surface::makeShared(Vector3D{0., 0., 0.}, Vector3D{0., 0., 1.}); - using TrackState = TrackState; - std::optional tso{std::nullopt}; std::unique_ptr> fm; + TestTrackState pc; if (dim == 3) { ActsMatrixD<3, 3> mCov; - // mCov << 1, 2, 3, 4, 5, 6, 7, 8, 9; mCov.setRandom(); Vector3D mPar; - // mPar << 2, 3, 4; mPar.setRandom(); Measurement meas{ plane, {}, mCov, mPar[0], mPar[1], mPar[2]}; fm = std::make_unique>(meas); - SourceLink sl{fm.get()}; - - TrackState ts{sl}; + SourceLink sourceLink{fm.get()}; + pc.sourceLink = sourceLink; + if (ACTS_CHECK_BIT(mask, TrackStatePropMask::Uncalibrated)) { + ts.uncalibrated() = sourceLink; + } // "calibrate", keep original source link (stack address) - ts.measurement.calibrated = - decltype(meas){meas.referenceSurface().getSharedPtr(), - sl, - meas.covariance(), - meas.parameters()[0], - meas.parameters()[1], - meas.parameters()[2]}; - tso = ts; + pc.meas3d = {meas.referenceSurface().getSharedPtr(), + sourceLink, + meas.covariance(), + meas.parameters()[0], + meas.parameters()[1], + meas.parameters()[2]}; + if (ACTS_CHECK_BIT(mask, TrackStatePropMask::Calibrated)) { + ts.setCalibrated(*pc.meas3d); + } } else if (dim == 2) { ActsMatrixD<2, 2> mCov; - // mCov << 1, 2, 3, 4; mCov.setRandom(); Vector2D mPar; - // mPar << 2, 3; mPar.setRandom(); Measurement meas{ plane, {}, mCov, mPar[0], mPar[1]}; fm = std::make_unique>(meas); - SourceLink sl{fm.get()}; - - TrackState ts{sl}; + SourceLink sourceLink{fm.get()}; + pc.sourceLink = sourceLink; + if (ACTS_CHECK_BIT(mask, TrackStatePropMask::Uncalibrated)) { + ts.uncalibrated() = sourceLink; + } // "calibrate", keep original source link (stack address) - ts.measurement.calibrated = decltype(meas){ - meas.referenceSurface().getSharedPtr(), sl, meas.covariance(), - meas.parameters()[0], meas.parameters()[1]}; - tso = ts; + pc.meas2d = {meas.referenceSurface().getSharedPtr(), sourceLink, + meas.covariance(), meas.parameters()[0], meas.parameters()[1]}; + if (ACTS_CHECK_BIT(mask, TrackStatePropMask::Calibrated)) { + ts.setCalibrated(*pc.meas2d); + } } else { throw std::runtime_error("wrong dim"); } - TrackState ts = *tso; - // add parameters // predicted @@ -122,8 +138,11 @@ auto make_trackstate(size_t dim = 3) { predCov.setRandom(); BoundParameters pred(gctx, predCov, predPar, plane); - - ts.parameter.predicted = pred; + pc.predicted = pred; + if (ACTS_CHECK_BIT(mask, TrackStatePropMask::Predicted)) { + ts.predicted() = pred.parameters(); + ts.predictedCovariance() = *pred.covariance(); + } // filtered ParVec_t filtPar; @@ -134,8 +153,11 @@ auto make_trackstate(size_t dim = 3) { filtCov.setRandom(); BoundParameters filt(gctx, filtCov, filtPar, plane); - - ts.parameter.filtered = filt; + pc.filtered = filt; + if (ACTS_CHECK_BIT(mask, TrackStatePropMask::Filtered)) { + ts.filtered() = filt.parameters(); + ts.filteredCovariance() = *filt.covariance(); + } // smoothed ParVec_t smotPar; @@ -146,22 +168,29 @@ auto make_trackstate(size_t dim = 3) { smotCov.setRandom(); BoundParameters smot(gctx, smotCov, smotPar, plane); - - ts.parameter.smoothed = smot; + pc.smoothed = smot; + if (ACTS_CHECK_BIT(mask, TrackStatePropMask::Smoothed)) { + ts.smoothed() = smot.parameters(); + ts.smoothedCovariance() = *smot.covariance(); + } // make jacobian CovMat_t jac; jac.setRandom(); - - ts.parameter.jacobian = jac; + pc.jacobian = jac; + if (ACTS_CHECK_BIT(mask, TrackStatePropMask::Jacobian)) { + ts.jacobian() = jac; + } std::random_device rd; std::mt19937 gen(rd()); std::uniform_real_distribution<> dis(1.0, 100.0); - ts.parameter.chi2 = dis(gen); - ts.parameter.pathLength = dis(gen); + pc.chi2 = dis(gen); + pc.pathLength = dis(gen); + ts.chi2() = pc.chi2; + ts.pathLength() = pc.pathLength; - return std::make_tuple(ts, std::move(fm)); + return std::make_tuple(pc, std::move(fm)); } BOOST_AUTO_TEST_CASE(multitrajectory_build) { @@ -169,12 +198,12 @@ BOOST_AUTO_TEST_CASE(multitrajectory_build) { TrackStatePropMask mask = TrackStatePropMask::Predicted; // construct trajectory w/ multiple components - auto i0 = t.addTrackState(make_rand_trackstate(), mask); + auto i0 = t.addTrackState(mask); // trajectory bifurcates here into multiple hypotheses - auto i1a = t.addTrackState(make_rand_trackstate(), mask, i0); - auto i1b = t.addTrackState(make_rand_trackstate(), mask, i0); - auto i2a = t.addTrackState(make_rand_trackstate(), mask, i1a); - auto i2b = t.addTrackState(make_rand_trackstate(), mask, i1b); + auto i1a = t.addTrackState(mask, i0); + auto i1b = t.addTrackState(mask, i0); + auto i2a = t.addTrackState(mask, i1a); + auto i2b = t.addTrackState(mask, i1b); // print each trajectory component std::vector act; @@ -207,9 +236,9 @@ BOOST_AUTO_TEST_CASE(visit_apply_abort) { TrackStatePropMask mask = TrackStatePropMask::Predicted; // construct trajectory with three components - auto i0 = t.addTrackState(make_rand_trackstate(), mask); - auto i1 = t.addTrackState(make_rand_trackstate(), mask, i0); - auto i2 = t.addTrackState(make_rand_trackstate(), mask, i1); + auto i0 = t.addTrackState(mask); + auto i1 = t.addTrackState(mask, i0); + auto i2 = t.addTrackState(mask, i1); size_t n = 0; t.applyBackwards(i2, [&](const auto&) { @@ -387,21 +416,21 @@ BOOST_AUTO_TEST_CASE(trackstate_add_bitmask_method) { BOOST_AUTO_TEST_CASE(trackstate_proxy_cross_talk) { // assert expected "cross-talk" between trackstate proxies - auto [ots, fm] = make_trackstate(); MultiTrajectory t; - - t.addTrackState(ots); + size_t index = t.addTrackState(); + auto tso = t.getTrackState(index); + auto [pc, fm] = fillTrackState(tso, TrackStatePropMask::All); const auto& ct = t; auto cts = ct.getTrackState(0); auto ts = t.getTrackState(0); // assert expected value of chi2 and path length - BOOST_CHECK_EQUAL(cts.chi2(), ots.parameter.chi2); - BOOST_CHECK_EQUAL(ts.chi2(), ots.parameter.chi2); - BOOST_CHECK_EQUAL(cts.pathLength(), ots.parameter.pathLength); - BOOST_CHECK_EQUAL(ts.pathLength(), ots.parameter.pathLength); + BOOST_CHECK_EQUAL(cts.chi2(), pc.chi2); + BOOST_CHECK_EQUAL(ts.chi2(), pc.chi2); + BOOST_CHECK_EQUAL(cts.pathLength(), pc.pathLength); + BOOST_CHECK_EQUAL(ts.pathLength(), pc.pathLength); ParVec_t v; CovMat_t cov; @@ -429,9 +458,9 @@ BOOST_AUTO_TEST_CASE(trackstate_proxy_cross_talk) { // make copy of fm auto fm2 = std::make_unique>(*fm); - SourceLink sl2{fm2.get()}; - ts.uncalibrated() = sl2; - BOOST_CHECK_EQUAL(cts.uncalibrated(), sl2); + SourceLink sourceLink2{fm2.get()}; + ts.uncalibrated() = sourceLink2; + BOOST_CHECK_EQUAL(cts.uncalibrated(), sourceLink2); BOOST_CHECK_NE(cts.uncalibrated(), SourceLink{fm.get()}); CovMat_t newMeasCov; @@ -466,25 +495,21 @@ BOOST_AUTO_TEST_CASE(trackstate_proxy_cross_talk) { } BOOST_AUTO_TEST_CASE(trackstate_reassignment) { - auto [ots, fm] = make_trackstate(); - constexpr size_t maxmeasdim = MultiTrajectory::MeasurementSizeMax; MultiTrajectory t; - t.addTrackState(ots); + size_t index = t.addTrackState(); + auto tso = t.getTrackState(index); + auto [pc, fm] = fillTrackState(tso, TrackStatePropMask::All); auto ts = t.getTrackState(0); - std::visit( - [&](auto meas) { - // assert measdim and contents of original measurement (just to be safe) - BOOST_CHECK_EQUAL(ts.calibratedSize(), meas.size()); - BOOST_CHECK_EQUAL(ts.effectiveCalibrated(), meas.parameters()); - BOOST_CHECK_EQUAL(ts.effectiveCalibratedCovariance(), - meas.covariance()); - BOOST_CHECK_EQUAL(ts.effectiveProjector(), meas.projector()); - }, - *ots.measurement.calibrated); + // assert measdim and contents of original measurement (just to be safe) + BOOST_CHECK_EQUAL(ts.calibratedSize(), pc.meas3d->size()); + BOOST_CHECK_EQUAL(ts.effectiveCalibrated(), pc.meas3d->parameters()); + BOOST_CHECK_EQUAL(ts.effectiveCalibratedCovariance(), + pc.meas3d->covariance()); + BOOST_CHECK_EQUAL(ts.effectiveProjector(), pc.meas3d->projector()); // create new measurement SymMatrix2D mCov; @@ -492,7 +517,7 @@ BOOST_AUTO_TEST_CASE(trackstate_reassignment) { Vector2D mPar; mPar.setRandom(); Measurement m2{ - ots.referenceSurface().getSharedPtr(), {}, mCov, mPar[0], mPar[1]}; + pc.meas3d->referenceSurface().getSharedPtr(), {}, mCov, mPar[0], mPar[1]}; ts.setCalibrated(m2); @@ -520,98 +545,87 @@ BOOST_AUTO_TEST_CASE(trackstate_reassignment) { BOOST_AUTO_TEST_CASE(storage_consistency) { MultiTrajectory t; + size_t index = t.addTrackState(); + auto ts = t.getTrackState(index); + auto [pc, fm] = fillTrackState(ts, TrackStatePropMask::All); + + // now investigate the proxy + // parameters + BOOST_CHECK(ts.hasPredicted()); + BOOST_CHECK_EQUAL(pc.predicted->parameters(), ts.predicted()); + BOOST_CHECK_EQUAL(*pc.predicted->covariance(), ts.predictedCovariance()); - auto [ts, fm] = make_trackstate(); + BOOST_CHECK(ts.hasFiltered()); + BOOST_CHECK_EQUAL(pc.filtered->parameters(), ts.filtered()); + BOOST_CHECK_EQUAL(*pc.filtered->covariance(), ts.filteredCovariance()); - // now put it into the collection - t.addTrackState(ts); + BOOST_CHECK(ts.hasSmoothed()); + BOOST_CHECK_EQUAL(pc.smoothed->parameters(), ts.smoothed()); + BOOST_CHECK_EQUAL(*pc.smoothed->covariance(), ts.smoothedCovariance()); - // now investigate the proxy - auto tsProxy = t.getTrackState(0); + BOOST_CHECK_EQUAL(&ts.referenceSurface(), &pc.sourceLink.referenceSurface()); - // parameters - BOOST_CHECK(tsProxy.hasPredicted()); - BOOST_CHECK_EQUAL(ts.parameter.predicted->parameters(), tsProxy.predicted()); - BOOST_CHECK_EQUAL(*ts.parameter.predicted->covariance(), - tsProxy.predictedCovariance()); - - BOOST_CHECK(tsProxy.hasFiltered()); - BOOST_CHECK_EQUAL(ts.parameter.filtered->parameters(), tsProxy.filtered()); - BOOST_CHECK_EQUAL(*ts.parameter.filtered->covariance(), - tsProxy.filteredCovariance()); - - BOOST_CHECK(tsProxy.hasSmoothed()); - BOOST_CHECK_EQUAL(ts.parameter.smoothed->parameters(), tsProxy.smoothed()); - BOOST_CHECK_EQUAL(*ts.parameter.smoothed->covariance(), - tsProxy.smoothedCovariance()); - - BOOST_CHECK_EQUAL(&tsProxy.referenceSurface(), &ts.referenceSurface()); - - BOOST_CHECK(tsProxy.hasJacobian()); - BOOST_CHECK_EQUAL(tsProxy.jacobian(), *ts.parameter.jacobian); - - BOOST_CHECK(tsProxy.hasProjector()); - std::visit( - [&](const auto& meas) { - BOOST_CHECK_EQUAL(tsProxy.effectiveProjector(), meas.projector()); - // measurement properties - BOOST_CHECK(tsProxy.hasCalibrated()); - BOOST_CHECK_EQUAL(meas.parameters(), tsProxy.effectiveCalibrated()); - ParVec_t mParFull; - mParFull.setZero(); - mParFull.head(meas.size()) = meas.parameters(); - BOOST_CHECK_EQUAL(mParFull, tsProxy.calibrated()); - - BOOST_CHECK_EQUAL(meas.covariance(), - tsProxy.effectiveCalibratedCovariance()); - CovMat_t mCovFull; - mCovFull.setZero(); - mCovFull.topLeftCorner(meas.size(), meas.size()) = meas.covariance(); - BOOST_CHECK_EQUAL(mCovFull, tsProxy.calibratedCovariance()); - - // calibrated links to original measurement - BOOST_CHECK_EQUAL(meas.sourceLink(), tsProxy.calibratedSourceLink()); - - // uncalibrated **is** a SourceLink - BOOST_CHECK(tsProxy.hasUncalibrated()); - BOOST_CHECK_EQUAL(meas.sourceLink(), tsProxy.uncalibrated()); - - // full projector, should be exactly equal - CovMat_t fullProj; - fullProj.setZero(); - fullProj.topLeftCorner( - meas.size(), MultiTrajectory::MeasurementSizeMax) = - meas.projector(); - BOOST_CHECK_EQUAL(tsProxy.projector(), fullProj); - - // projector with dynamic rows - // should be exactly equal - BOOST_CHECK_EQUAL(tsProxy.effectiveProjector(), meas.projector()); - }, - *ts.measurement.calibrated); -} + BOOST_CHECK(ts.hasJacobian()); + BOOST_CHECK_EQUAL(ts.jacobian(), pc.jacobian); -BOOST_AUTO_TEST_CASE(add_trackstate_allocations) { - auto [ts, fm] = make_trackstate(); + BOOST_CHECK(ts.hasProjector()); + BOOST_CHECK_EQUAL(ts.effectiveProjector(), pc.meas3d->projector()); + // measurement properties + BOOST_CHECK(ts.hasCalibrated()); + BOOST_CHECK_EQUAL(pc.meas3d->parameters(), ts.effectiveCalibrated()); + ParVec_t mParFull; + mParFull.setZero(); + mParFull.head(pc.meas3d->size()) = pc.meas3d->parameters(); + BOOST_CHECK_EQUAL(mParFull, ts.calibrated()); - ts.parameter.filtered = std::nullopt; - ts.parameter.smoothed = std::nullopt; - ts.measurement.calibrated = std::nullopt; + BOOST_CHECK_EQUAL(pc.meas3d->covariance(), + ts.effectiveCalibratedCovariance()); + CovMat_t mCovFull; + mCovFull.setZero(); + mCovFull.topLeftCorner(pc.meas3d->size(), pc.meas3d->size()) = + pc.meas3d->covariance(); + BOOST_CHECK_EQUAL(mCovFull, ts.calibratedCovariance()); - MultiTrajectory mj; + // calibrated links to original measurement + BOOST_CHECK_EQUAL(pc.meas3d->sourceLink(), ts.calibratedSourceLink()); - // this should allocate for all the components in the trackstate, plus - // filtered - size_t i = mj.addTrackState(ts, TrackStatePropMask::Filtered); + // uncalibrated **is** a SourceLink + BOOST_CHECK(ts.hasUncalibrated()); + BOOST_CHECK_EQUAL(pc.meas3d->sourceLink(), ts.uncalibrated()); + + // full projector, should be exactly equal + CovMat_t fullProj; + fullProj.setZero(); + fullProj.topLeftCorner(pc.meas3d->size(), + MultiTrajectory::MeasurementSizeMax) = + pc.meas3d->projector(); + BOOST_CHECK_EQUAL(ts.projector(), fullProj); + + // projector with dynamic rows + // should be exactly equal + BOOST_CHECK_EQUAL(ts.effectiveProjector(), pc.meas3d->projector()); +} - auto tsp = mj.getTrackState(i); +BOOST_AUTO_TEST_CASE(add_trackstate_allocations) { + MultiTrajectory t; - BOOST_CHECK(tsp.hasPredicted()); - BOOST_CHECK(tsp.hasFiltered()); - BOOST_CHECK(!tsp.hasSmoothed()); - BOOST_CHECK(tsp.hasUncalibrated()); - BOOST_CHECK(!tsp.hasCalibrated()); - BOOST_CHECK(tsp.hasJacobian()); + // this should allocate for all the components in the trackstate, plus + // filtered + size_t i = t.addTrackState( + TrackStatePropMask::Predicted | TrackStatePropMask::Filtered | + TrackStatePropMask::Uncalibrated | TrackStatePropMask::Jacobian); + auto tso = t.getTrackState(i); + fillTrackState(tso, TrackStatePropMask::Predicted); + fillTrackState(tso, TrackStatePropMask::Filtered); + fillTrackState(tso, TrackStatePropMask::Uncalibrated); + fillTrackState(tso, TrackStatePropMask::Jacobian); + + BOOST_CHECK(tso.hasPredicted()); + BOOST_CHECK(tso.hasFiltered()); + BOOST_CHECK(!tso.hasSmoothed()); + BOOST_CHECK(tso.hasUncalibrated()); + BOOST_CHECK(!tso.hasCalibrated()); + BOOST_CHECK(tso.hasJacobian()); // remove some parts } @@ -692,13 +706,12 @@ BOOST_AUTO_TEST_CASE(trackstateproxy_copy) { BOOST_CHECK(ts1.predicted() == ts2.predicted()); BOOST_CHECK(ts1.predictedCovariance() == ts2.predictedCovariance()); - auto [rts1, fm1] = make_trackstate(2); - auto [rts2, fm2] = make_trackstate(3); - auto i0 = mj.addTrackState(rts1); - auto i1 = mj.addTrackState(rts2); - + size_t i0 = mj.addTrackState(); + size_t i1 = mj.addTrackState(); ts1 = mj.getTrackState(i0); ts2 = mj.getTrackState(i1); + auto [rts1, fm1] = fillTrackState(ts1, TrackStatePropMask::All, 2); + auto [rts2, fm2] = fillTrackState(ts2, TrackStatePropMask::All, 3); auto ots1 = mkts(PM::All); auto ots2 = mkts(PM::All); diff --git a/Tests/UnitTests/Core/EventData/TrackStateTests.cpp b/Tests/UnitTests/Core/EventData/TrackStateTests.cpp deleted file mode 100644 index 9a460fc5296..00000000000 --- a/Tests/UnitTests/Core/EventData/TrackStateTests.cpp +++ /dev/null @@ -1,196 +0,0 @@ -// This file is part of the Acts project. -// -// Copyright (C) 2016-2018 CERN for the benefit of the Acts project -// -// This Source Code Form is subject to the terms of the Mozilla Public -// License, v. 2.0. If a copy of the MPL was not distributed with this -// file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include -#include - -#include -#include "Acts/EventData/Measurement.hpp" -#include "Acts/EventData/MeasurementHelpers.hpp" -#include "Acts/EventData/TrackParameters.hpp" -#include "Acts/EventData/TrackState.hpp" -#include "Acts/EventData/TrackStateSorters.hpp" -#include "Acts/Surfaces/PlaneSurface.hpp" -#include "Acts/Utilities/Definitions.hpp" -#include "Acts/Utilities/ParameterDefinitions.hpp" - -namespace Acts { -namespace Test { - -// Create a test context -GeometryContext tgContext = GeometryContext(); - -using SourceLink = MinimalSourceLink; - -template -using MeasurementType = Measurement; -using FittableMeasurement = FittableMeasurement; -using BoundTrackState = TrackState; -/// -/// @brief Unit test for creation of Measurement object -/// -BOOST_AUTO_TEST_CASE(track_state_initialization) { - std::default_random_engine generator(42); - - // The plane surface - auto plane = Surface::makeShared(Vector3D{0., 0., 0.}, - Vector3D{1., 0., 0.}); - - // Construct the 1D measurement - ActsSymMatrixD<1> cov1D; - cov1D << 0.04; - - FittableMeasurement m1D( - MeasurementType(plane, {}, std::move(cov1D), 0.02)); - - // Construct the 2D measurement - SymMatrix2D cov2D; - cov2D << 0.04, 0., 0.09, 0.; - - FittableMeasurement m2D(MeasurementType( - plane, {}, std::move(cov2D), 0.02, 0.03)); - - // The 1D track state from the measurement - BoundTrackState mts1D(SourceLink{&m1D}); - - auto calibrate = [](auto& trackstate) { - // double ref: optional, MinimalSourceLink - trackstate.measurement.calibrated = **trackstate.measurement.uncalibrated; - }; - - // "calibrate" the measurement - calibrate(mts1D); - - BOOST_CHECK_EQUAL(*mts1D.size(), 1u); - - // Test the copy construtor - BoundTrackState mts1DCopy(mts1D); - - // Test the copy move constructor - BoundTrackState mts1DCopyMoved(std::move(mts1DCopy)); - - // Test the copy assignment operator - BoundTrackState mts1DCopyAssigned = mts1DCopyMoved; - - // Test the comovepy assignment operator - BoundTrackState mts1DMoveAssigned = std::move(mts1DCopyAssigned); - - // Swap the measurements - std::swap(mts1DMoveAssigned, mts1D); - - // The 2D track state from the measurement - BoundTrackState mts2D(SourceLink{&m2D}); - calibrate(mts2D); - - BOOST_CHECK_EQUAL(*mts2D.size(), 2u); - - // Construct the parameter - std::array pars_array = { - {-0.1234, 9.8765, 0.45, 0.888, 0.001, 0.}}; - BoundVector pars; - pars << pars_array[0], pars_array[1], pars_array[2], pars_array[3], - pars_array[4], pars_array[5]; - - // constructor from parameter vector: predicted filtered, smoothed - BoundParameters ataPlane(tgContext, std::nullopt, pars, plane); - - // The parameter track state from the parameters - BoundTrackState pts(std::move(ataPlane)); - - // Test the copy constructor for a parameter state - BoundTrackState ptsCopy(pts); - - // Test the copy move constructor for a parameter state - BoundTrackState ptsCopyMove(std::move(ptsCopy)); - - // Test the copy assignment for a parameter state - BoundTrackState ptsCopyAssigned = ptsCopyMove; - - // Test the move assignment for a parameter state - BoundTrackState ptsMoveAssigned = std::move(ptsCopyAssigned); - - std::vector trackStates = {std::move(mts1DMoveAssigned), - std::move(mts2D), std::move(pts)}; - - BOOST_CHECK_EQUAL(trackStates.size(), 3u); - - // Test is we can shuffle the track states - // Test to extract the surface of these guys - for (auto& ts : trackStates) { - const Surface* sf = &ts.referenceSurface(); - BOOST_CHECK_EQUAL(sf, plane.get()); - } - - // Create predicted, filtered and smoothed parameters - BoundParameters ataPlaneUpdt(tgContext, std::nullopt, pars, plane); - BoundParameters ataPlanePred(tgContext, std::nullopt, pars, plane); - BoundParameters ataPlaneSmth(tgContext, std::nullopt, pars, plane); - - // Get the predicted parameters back from the trackState - auto& ptsfList = trackStates[2]; - auto& ataPlanefListPred = ptsfList.parameter.predicted; - BOOST_CHECK(ataPlanefListPred); - - // Check that the other parameters are empty - auto& ataPlanefListUpdt = ptsfList.parameter.filtered; - BOOST_CHECK(!ataPlanefListUpdt); - - auto& ataPlanefListSmthd = ptsfList.parameter.smoothed; - BOOST_CHECK(!ataPlanefListSmthd); - - // Get the track States from the list - auto& m2DfList = trackStates[1]; - - m2DfList.parameter.filtered = std::move(ataPlaneUpdt); - auto& ataPlanefListUpdtM2D = m2DfList.parameter.filtered; - BOOST_CHECK(ataPlanefListUpdtM2D); - - m2DfList.parameter.predicted = std::move(ataPlanePred); - auto& ataPlanefListPred2D = m2DfList.parameter.predicted; - BOOST_CHECK(ataPlanefListPred2D); - - // Test the sorting helper - BoundParameters ataPlaneAt1(tgContext, std::nullopt, pars, plane); - BoundTrackState ataPlaneState1(std::move(ataPlaneAt1)); - ataPlaneState1.parameter.pathLength = 1.; - - BoundParameters ataPlaneAt2(tgContext, std::nullopt, pars, plane); - BoundTrackState ataPlaneState2(std::move(ataPlaneAt2)); - ataPlaneState2.parameter.pathLength = 2.; - - std::vector unorderedStates = {std::move(ataPlaneState2), - std::move(ataPlaneState1)}; - - // Sort the variant track state - TrackStatePathLengthSorter plSorter; - std::sort(unorderedStates.begin(), unorderedStates.end(), plSorter); - - auto firstOrdered = unorderedStates[0]; - BOOST_CHECK_EQUAL(firstOrdered.parameter.pathLength, 1.); - - auto secondOrdered = unorderedStates[1]; - BOOST_CHECK_EQUAL(secondOrdered.parameter.pathLength, 2.); - - auto& pState = firstOrdered.parameter; - - BOOST_CHECK_EQUAL(pState.pathLength, 1.); - - std::shuffle(unorderedStates.begin(), unorderedStates.end(), generator); - - // Copy the TrackStates into a new vector - std::vector copiedStates = {unorderedStates[0], - unorderedStates[1]}; - - // Shuffle - std::shuffle(copiedStates.begin(), copiedStates.end(), generator); - // And sort again - std::sort(copiedStates.begin(), copiedStates.end(), plSorter); -} - -} // namespace Test -} // namespace Acts diff --git a/Tests/UnitTests/Core/Fitter/GainMatrixSmootherTests.cpp b/Tests/UnitTests/Core/Fitter/GainMatrixSmootherTests.cpp index 204a4039d0d..095a2fa8926 100644 --- a/Tests/UnitTests/Core/Fitter/GainMatrixSmootherTests.cpp +++ b/Tests/UnitTests/Core/Fitter/GainMatrixSmootherTests.cpp @@ -13,7 +13,6 @@ #include "Acts/EventData/Measurement.hpp" #include "Acts/EventData/MeasurementHelpers.hpp" -#include "Acts/EventData/TrackState.hpp" #include "Acts/Fitter/GainMatrixSmoother.hpp" #include "Acts/Surfaces/CylinderSurface.hpp" #include "Acts/Tests/CommonHelpers/FloatComparisons.hpp" @@ -29,7 +28,6 @@ using SourceLink = MinimalSourceLink; template using MeasurementType = Measurement; -using TrackState = TrackState; // Create a test context GeometryContext tgContext = GeometryContext(); diff --git a/Tests/UnitTests/Core/Fitter/GainMatrixUpdaterTests.cpp b/Tests/UnitTests/Core/Fitter/GainMatrixUpdaterTests.cpp index af211cc709e..3649efe9c61 100644 --- a/Tests/UnitTests/Core/Fitter/GainMatrixUpdaterTests.cpp +++ b/Tests/UnitTests/Core/Fitter/GainMatrixUpdaterTests.cpp @@ -14,7 +14,6 @@ #include "Acts/EventData/Measurement.hpp" #include "Acts/EventData/MeasurementHelpers.hpp" #include "Acts/EventData/TrackParameters.hpp" -#include "Acts/EventData/TrackState.hpp" #include "Acts/Fitter/GainMatrixUpdater.hpp" #include "Acts/Surfaces/CylinderSurface.hpp" #include "Acts/Tests/CommonHelpers/FloatComparisons.hpp" @@ -30,7 +29,6 @@ using SourceLink = MinimalSourceLink; template using MeasurementType = Measurement; -using TrackState = TrackState; // Create a test context GeometryContext tgContext = GeometryContext(); diff --git a/Tests/UnitTests/Core/Fitter/KalmanFitterTests.cpp b/Tests/UnitTests/Core/Fitter/KalmanFitterTests.cpp index 7267e2671a8..898b3210c66 100644 --- a/Tests/UnitTests/Core/Fitter/KalmanFitterTests.cpp +++ b/Tests/UnitTests/Core/Fitter/KalmanFitterTests.cpp @@ -17,7 +17,6 @@ #include "Acts/EventData/Measurement.hpp" #include "Acts/EventData/MeasurementHelpers.hpp" #include "Acts/EventData/TrackParameters.hpp" -#include "Acts/EventData/TrackState.hpp" #include "Acts/Fitter/GainMatrixSmoother.hpp" #include "Acts/Fitter/GainMatrixUpdater.hpp" #include "Acts/Fitter/KalmanFitter.hpp" @@ -51,7 +50,6 @@ using SourceLink = MinimalSourceLink; using Jacobian = BoundParameters::CovMatrix_t; using Covariance = BoundSymMatrix; -using TrackState = TrackState; using Resolution = std::pair; using ElementResolution = std::vector; using VolumeResolution = std::map; diff --git a/Tests/UnitTests/Core/Visualization/EventDataViewBase.hpp b/Tests/UnitTests/Core/Visualization/EventDataViewBase.hpp index 9b4ac703b39..feda6df50d7 100644 --- a/Tests/UnitTests/Core/Visualization/EventDataViewBase.hpp +++ b/Tests/UnitTests/Core/Visualization/EventDataViewBase.hpp @@ -11,7 +11,6 @@ #include "Acts/EventData/Measurement.hpp" #include "Acts/EventData/MeasurementHelpers.hpp" #include "Acts/EventData/TrackParameters.hpp" -#include "Acts/EventData/TrackState.hpp" #include "Acts/Fitter/GainMatrixSmoother.hpp" #include "Acts/Fitter/GainMatrixUpdater.hpp" #include "Acts/Fitter/KalmanFitter.hpp"