Skip to content

Commit

Permalink
refactor!: MTJ stores measurement as jagged vector (#1512)
Browse files Browse the repository at this point in the history
Addresses #1516.

```
 | x x x | x | x x |  ...
   ^       ^     ^
 M1,D=3 M2,D=1 M3,D=2
```

BREAKING CHANGE: `Acts::MultiTrajectory` measurement access methods change:
```diff
- constexpr auto measurement(IndexType measIdx) const;
+ template <size_t measdim> 
+ constexpr auto measurement(IndexType measIdx) const;
```
and 
```diff
- constexpr auto measurementCovariance(IndexType covIdx)
+ template <size_t measdim>
+ constexpr auto measurementCovariance(IndexType covIdx)
```
  • Loading branch information
paulgessinger authored Oct 31, 2022
1 parent 5c07814 commit 5b802fc
Show file tree
Hide file tree
Showing 19 changed files with 508 additions and 239 deletions.
12 changes: 12 additions & 0 deletions Core/include/Acts/EventData/MeasurementHelpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,4 +57,16 @@ auto visit_measurement(A&& param, B&& cov, size_t dim, L&& lambda) {
dim, param, cov, lambda);
}

/// Dispatch a generic lambda on a measurement dimension. This overload doesn't
/// assume anything about what is needed inside the lambda, it communicates the
/// dimension via an integral constant type
/// @tparam L The generic lambda type to call
/// @param dim The runtime dimension of the measurement
/// @param lambda The generic lambda instance to call
/// @return Returns the lambda return value
template <typename L>
auto visit_measurement(size_t dim, L&& lambda) {
return template_switch_lambda<1, eBoundSize>(dim, lambda);
}

} // namespace Acts
143 changes: 112 additions & 31 deletions Core/include/Acts/EventData/MultiTrajectory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

#include "Acts/Definitions/TrackParametrization.hpp"
#include "Acts/EventData/Measurement.hpp"
#include "Acts/EventData/MeasurementHelpers.hpp"
#include "Acts/EventData/SourceLink.hpp"
#include "Acts/EventData/TrackStatePropMask.hpp"
#include "Acts/Geometry/GeometryContext.hpp"
Expand Down Expand Up @@ -67,6 +68,14 @@ struct Types {
using Covariance = Eigen::Matrix<Scalar, Size, Size, Flags>;
using CoefficientsMap = Eigen::Map<ConstIf<Coefficients, ReadOnlyMaps>>;
using CovarianceMap = Eigen::Map<ConstIf<Covariance, ReadOnlyMaps>>;

using DynamicCoefficients = Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Flags>;
using DynamicCovariance =
Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Flags>;
using DynamicCoefficientsMap =
Eigen::Map<ConstIf<DynamicCoefficients, ReadOnlyMaps>>;
using DynamicCovarianceMap =
Eigen::Map<ConstIf<DynamicCovariance, ReadOnlyMaps>>;
};
} // namespace detail_lt

Expand Down Expand Up @@ -101,9 +110,12 @@ class TrackStateProxy {
public:
using Parameters = typename TrackStateTraits<M, ReadOnly>::Parameters;
using Covariance = typename TrackStateTraits<M, ReadOnly>::Covariance;
using Measurement = typename TrackStateTraits<M, ReadOnly>::Measurement;

template <size_t N>
using Measurement = typename TrackStateTraits<N, ReadOnly>::Measurement;
template <size_t N>
using MeasurementCovariance =
typename TrackStateTraits<M, ReadOnly>::MeasurementCovariance;
typename TrackStateTraits<N, ReadOnly>::MeasurementCovariance;

using IndexType = typename TrackStateTraits<M, ReadOnly>::IndexType;
static constexpr IndexType kInvalid = TrackStateTraits<M, ReadOnly>::kInvalid;
Expand Down Expand Up @@ -223,8 +235,17 @@ class TrackStateProxy {
auto dest = getMask();
auto src = other.getMask() &
mask; // combine what we have with what we want to copy
if (static_cast<std::underlying_type_t<TrackStatePropMask>>((src ^ dest) &
src) != 0) {

if (ACTS_CHECK_BIT(src, PM::Calibrated)) {
// on-demand allocate calibrated
dest |= PM::Calibrated;
}

if ((static_cast<std::underlying_type_t<TrackStatePropMask>>(
(src ^ dest) & src) != 0 ||
dest == TrackStatePropMask::None ||
src == TrackStatePropMask::None) &&
mask != TrackStatePropMask::None) {
throw std::runtime_error(
"Attempt track state copy with incompatible allocations");
}
Expand Down Expand Up @@ -259,9 +280,19 @@ class TrackStateProxy {
component<const SourceLink*, hashString("calibratedSourceLink")>() =
other.template component<const SourceLink*,
hashString("calibratedSourceLink")>();
calibrated() = other.calibrated();
calibratedCovariance() = other.calibratedCovariance();
calibratedSize() = other.calibratedSize();
allocateCalibrated(other.calibratedSize());

// workaround for gcc8 bug:
// https://gcc.gnu.org/bugzilla/show_bug.cgi?id=86594
auto* self = this;
visit_measurement(other.calibratedSize(), [&](auto N) {
constexpr int measdim = decltype(N)::value;
self->template calibrated<measdim>() =
other.template calibrated<measdim>();
self->template calibratedCovariance<measdim>() =
other.template calibratedCovariance<measdim>();
});

setProjectorBitset(other.projectorBitset());
}
} else {
Expand Down Expand Up @@ -303,9 +334,20 @@ class TrackStateProxy {
component<const SourceLink*, hashString("calibratedSourceLink")>() =
other.template component<const SourceLink*,
hashString("calibratedSourceLink")>();
calibrated() = other.calibrated();
calibratedCovariance() = other.calibratedCovariance();
calibratedSize() = other.calibratedSize();

allocateCalibrated(other.calibratedSize());

// workaround for gcc8 bug:
// https://gcc.gnu.org/bugzilla/show_bug.cgi?id=86594
auto* self = this;
visit_measurement(other.calibratedSize(), [&](auto N) {
constexpr int measdim = decltype(N)::value;
self->template calibrated<measdim>() =
other.template calibrated<measdim>();
self->template calibratedCovariance<measdim>() =
other.template calibratedCovariance<measdim>();
});

setProjectorBitset(other.projectorBitset());
}
}
Expand Down Expand Up @@ -578,24 +620,43 @@ class TrackStateProxy {
/// Full calibrated measurement vector. Might contain additional zeroed
/// dimensions.
/// @return The measurement vector
Measurement calibrated() const;
template <size_t measdim>
Measurement<measdim> calibrated() const;

/// Full calibrated measurement covariance matrix. The effective covariance
/// is located in the top left corner, everything else is zeroed.
/// @return The measurement covariance matrix
MeasurementCovariance calibratedCovariance() const;
template <size_t measdim>
MeasurementCovariance<measdim> calibratedCovariance() const;

/// Dynamic measurement vector with only the valid dimensions.
/// @return The effective calibrated measurement vector
auto effectiveCalibrated() const {
return calibrated().head(calibratedSize());
// repackage the data pointer to a dynamic map type
// workaround for gcc8 bug:
// https://gcc.gnu.org/bugzilla/show_bug.cgi?id=86594
auto* self = this;
return visit_measurement(calibratedSize(), [&](auto N) {
constexpr int kMeasurementSize = decltype(N)::value;
return typename Types<M, ReadOnly>::DynamicCoefficientsMap{
self->template calibrated<kMeasurementSize>().data(),
kMeasurementSize};
});
}

/// Dynamic measurement covariance matrix with only the valid dimensions.
/// @return The effective calibrated covariance matrix
auto effectiveCalibratedCovariance() const {
const size_t measdim = calibratedSize();
return calibratedCovariance().topLeftCorner(measdim, measdim);
// repackage the data pointer to a dynamic map type
// workaround for gcc8 bug:
// https://gcc.gnu.org/bugzilla/show_bug.cgi?id=86594
auto* self = this;
return visit_measurement(calibratedSize(), [&](auto N) {
constexpr int kMeasurementSize = decltype(N)::value;
return typename Types<M, ReadOnly>::DynamicCovarianceMap{
self->template calibratedCovariance<kMeasurementSize>().data(),
kMeasurementSize, kMeasurementSize};
});
}

/// Return the (dynamic) number of dimensions stored for this measurement.
Expand Down Expand Up @@ -642,16 +703,24 @@ class TrackStateProxy {
(component<const SourceLink*, hashString("calibratedSourceLink")>() !=
nullptr));

allocateCalibrated(kMeasurementSize);
assert(hasCalibrated());
calibrated().setZero();
calibrated().template head<kMeasurementSize>() = meas.parameters();
calibratedCovariance().setZero();
calibratedCovariance()

calibrated<kMeasurementSize>().setZero();
calibrated<kMeasurementSize>().template head<kMeasurementSize>() =
meas.parameters();
calibratedCovariance<kMeasurementSize>().setZero();
calibratedCovariance<kMeasurementSize>()
.template topLeftCorner<kMeasurementSize, kMeasurementSize>() =
meas.covariance();
setProjector(meas.projector());
}

void allocateCalibrated(size_t measdim) {
m_traj->allocateCalibrated(m_istate, measdim);
calibratedSize() = measdim;
}

/// Getter/setter for chi2 value associated with the track state
/// This overload returns a mutable reference, which allows setting a new
/// value directly into the backing store.
Expand Down Expand Up @@ -979,39 +1048,47 @@ class MultiTrajectory {
}

/// Retrieve a measurement proxy instance for a measurement at a given index
/// @tparam measdim the measurement dimension
/// @param measIdx Index into the measurement column
/// @return Mutable proxy
template <bool RO = ReadOnly, typename = std::enable_if_t<!RO>>
constexpr typename TrackStateProxy::Measurement measurement(
template <size_t measdim, bool RO = ReadOnly,
typename = std::enable_if_t<!RO>>
constexpr typename TrackStateProxy::template Measurement<measdim> measurement(
IndexType measIdx) {
return self().measurement_impl(measIdx);
return self().template measurement_impl<measdim>(measIdx);
}

/// Retrieve a measurement proxy instance for a measurement at a given index
/// @tparam measdim the measurement dimension
/// @param measIdx Index into the measurement column
/// @return Const proxy
constexpr typename ConstTrackStateProxy::Measurement measurement(
IndexType measIdx) const {
return self().measurement_impl(measIdx);
template <size_t measdim>
constexpr typename ConstTrackStateProxy::template Measurement<measdim>
measurement(IndexType measIdx) const {
return self().template measurement_impl<measdim>(measIdx);
}

/// Retrieve a measurement covariance proxy instance for a measurement at a
/// given index
/// @tparam measdim the measurement dimension
/// @param covIdx Index into the measurement covariance column
/// @return Mutable proxy
template <bool RO = ReadOnly, typename = std::enable_if_t<!RO>>
constexpr typename TrackStateProxy::MeasurementCovariance
template <size_t measdim, bool RO = ReadOnly,
typename = std::enable_if_t<!RO>>
constexpr typename TrackStateProxy::template MeasurementCovariance<measdim>
measurementCovariance(IndexType covIdx) {
return self().measurementCovariance_impl(covIdx);
return self().template measurementCovariance_impl<measdim>(covIdx);
}

/// Retrieve a measurement covariance proxy instance for a measurement at a
/// given index
/// @param covIdx Index into the measurement covariance column
/// @return Const proxy
constexpr typename ConstTrackStateProxy::MeasurementCovariance
measurementCovariance(IndexType covIdx) const {
return self().measurementCovariance_impl(covIdx);
template <size_t measdim>
constexpr
typename ConstTrackStateProxy::template MeasurementCovariance<measdim>
measurementCovariance(IndexType covIdx) const {
return self().template measurementCovariance_impl<measdim>(covIdx);
}

/// Share a shareable component from between track state.
Expand Down Expand Up @@ -1084,6 +1161,10 @@ class MultiTrajectory {
return *std::any_cast<const T*>(self().component_impl(key, istate));
}

void allocateCalibrated(IndexType istate, size_t measdim) {
self().allocateCalibrated_impl(istate, measdim);
}

private:
friend class detail_lt::TrackStateProxy<Derived, MeasurementSizeMax, true>;
friend class detail_lt::TrackStateProxy<Derived, MeasurementSizeMax, false>;
Expand Down
15 changes: 9 additions & 6 deletions Core/include/Acts/EventData/MultiTrajectory.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -138,9 +138,11 @@ inline auto TrackStateProxy<D, M, ReadOnly>::uncalibrated() const
}

template <typename D, size_t M, bool ReadOnly>
inline auto TrackStateProxy<D, M, ReadOnly>::calibrated() const -> Measurement {
template <size_t measdim>
inline auto TrackStateProxy<D, M, ReadOnly>::calibrated() const
-> Measurement<measdim> {
assert(has<hashString("calibrated")>());
return m_traj->self().measurement(
return m_traj->self().template measurement<measdim>(
component<IndexType, hashString("calibrated")>());
}

Expand All @@ -156,11 +158,12 @@ inline auto TrackStateProxy<D, M, ReadOnly>::calibratedSourceLink() const
}

template <typename D, size_t M, bool ReadOnly>
template <size_t measdim>
inline auto TrackStateProxy<D, M, ReadOnly>::calibratedCovariance() const
-> MeasurementCovariance {
assert(has<hashString("calibrated")>());
return m_traj->self().measurementCovariance(
component<IndexType, hashString("calibrated")>());
-> MeasurementCovariance<measdim> {
assert(has<hashString("calibratedCov")>());
return m_traj->self().template measurementCovariance<measdim>(
component<IndexType, hashString("calibratedCov")>());
}

} // namespace detail_lt
Expand Down
Loading

0 comments on commit 5b802fc

Please sign in to comment.