Skip to content

Commit

Permalink
Merge branch 'main' into refactor-rootmeasurementwriter
Browse files Browse the repository at this point in the history
  • Loading branch information
kodiakhq[bot] authored Jul 23, 2024
2 parents f3c08b5 + 94cf81f commit f4e757f
Show file tree
Hide file tree
Showing 58 changed files with 777 additions and 301 deletions.
9 changes: 8 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -222,10 +222,17 @@ set(_acts_boost_recommended_version 1.78.0)
# Include the sources for the external dependencies.
include(ActsExternSources)

# Controls behavior of DOWNLOAD_EXTRACT_TIMESTAMP
if(POLICY CMP0135)
cmake_policy(SET CMP0135 NEW)
endif()

# required packages
if (ACTS_SETUP_BOOST)
if (ACTS_USE_SYSTEM_BOOST)
# NOTE FindBoost.cmake looks for BoostConfig.cmake first, before running it's own logic.
if(POLICY CMP0167)
cmake_policy(SET CMP0167 NEW)
endif()

# Enable both program_options and unit_test_framework to reduce complexity
# Also Cuda tests seem to use program_options
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ class ScoreBasedAmbiguityResolution {
/// good enough, based on some criteria. Users are free to add their own cuts
/// with the help of this struct.
template <typename track_container_t, typename traj_t,
template <typename> class holder_t, bool ReadOnly>
template <typename> class holder_t, bool ReadOnly = true>
struct OptionalCuts {
using OptionalFilter =
std::function<bool(const Acts::TrackProxy<track_container_t, traj_t,
Expand Down Expand Up @@ -162,7 +162,7 @@ class ScoreBasedAmbiguityResolution {
/// @param optionalCuts is the user defined optional cuts to be applied.
/// @return a vector of scores for each track
template <typename track_container_t, typename traj_t,
template <typename> class holder_t, bool ReadOnly>
template <typename> class holder_t, bool ReadOnly = true>
std::vector<double> simpleScore(
const TrackContainer<track_container_t, traj_t, holder_t>& tracks,
const std::vector<std::vector<TrackFeatures>>& trackFeaturesVectors,
Expand All @@ -176,7 +176,7 @@ class ScoreBasedAmbiguityResolution {
/// @param optionalCuts is the user defined optional cuts to be applied.
/// @return a vector of scores for each track
template <typename track_container_t, typename traj_t,
template <typename> class holder_t, bool ReadOnly>
template <typename> class holder_t, bool ReadOnly = true>
std::vector<double> ambiguityScore(
const TrackContainer<track_container_t, traj_t, holder_t>& tracks,
const std::vector<std::vector<TrackFeatures>>& trackFeaturesVectors,
Expand Down Expand Up @@ -206,7 +206,7 @@ class ScoreBasedAmbiguityResolution {
/// @param optionalCuts is the optional cuts to be applied
/// @return a vector of IDs of the tracks we want to keep
template <typename track_container_t, typename traj_t,
template <typename> class holder_t, bool ReadOnly>
template <typename> class holder_t, bool ReadOnly = true>
std::vector<int> solveAmbiguity(
const TrackContainer<track_container_t, traj_t, holder_t>& tracks,
const std::vector<std::vector<MeasurementInfo>>& measurementsPerTrack,
Expand Down
6 changes: 4 additions & 2 deletions Core/include/Acts/EventData/TrackProxy.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -689,12 +689,14 @@ class TrackProxy {
reverseTrackStates();
}

parameters() = other.parameters();
covariance() = other.covariance();
setParticleHypothesis(other.particleHypothesis());

if (other.hasReferenceSurface()) {
setReferenceSurface(other.referenceSurface().getSharedPtr());
parameters() = other.parameters();
covariance() = other.covariance();
}

nMeasurements() = other.nMeasurements();
nHoles() = other.nHoles();
nOutliers() = other.nOutliers();
Expand Down
2 changes: 1 addition & 1 deletion Core/include/Acts/Navigation/NavigationStateUpdaters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ inline void updateCandidates(const GeometryContext& gctx,
gctx, position, direction, c.boundaryTolerance, s_onSurfaceTolerance);
for (auto& si : sIntersection.split()) {
c.objectIntersection = si;
if (c.objectIntersection &&
if (c.objectIntersection.isValid() &&
c.objectIntersection.pathLength() > overstepTolerance) {
nextSurfaceCandidates.emplace_back(c);
}
Expand Down
6 changes: 3 additions & 3 deletions Core/include/Acts/Propagator/DirectNavigator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,7 @@ class DirectNavigator {
<< state.navigation.currentSurface->geometryId());
// Move the sequence to the next surface
++state.navigation.surfaceIndex;
if (state.navigation.surfaceIndex >=
if (state.navigation.surfaceIndex <
state.navigation.options.surfaces.size()) {
ACTS_VERBOSE("Next surface candidate is "
<< state.navigation.options.surfaces
Expand All @@ -277,8 +277,8 @@ class DirectNavigator {
boundaryTolerance, tolerance);

for (auto& intersection : intersections.split()) {
if (detail::checkIntersection(intersection, nearLimit, farLimit,
logger())) {
if (detail::checkPathLength(intersection.pathLength(), nearLimit,
farLimit, logger())) {
return intersection;
}
}
Expand Down
2 changes: 1 addition & 1 deletion Core/include/Acts/Propagator/Navigator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -989,7 +989,7 @@ class Navigator {
state.options.direction * stepper.direction(state.stepping),
BoundaryTolerance::Infinite(), state.options.surfaceTolerance)
.closest();
if (targetIntersection) {
if (targetIntersection.isValid()) {
ACTS_VERBOSE(volInfo(state)
<< "Target estimate position ("
<< targetIntersection.position().x() << ", "
Expand Down
6 changes: 3 additions & 3 deletions Core/include/Acts/Propagator/StandardAborters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,9 +130,9 @@ struct SurfaceReached {
bool intersectionFound = false;

for (const auto& intersection : sIntersection.split()) {
if (intersection &&
detail::checkIntersection(intersection.intersection(), nearLimit,
farLimit, logger)) {
if (intersection.isValid() &&
detail::checkPathLength(intersection.pathLength(), nearLimit,
farLimit, logger)) {
stepper.updateStepSize(state.stepping, intersection.pathLength(),
ConstrainedStep::aborter, false);
ACTS_VERBOSE(
Expand Down
28 changes: 19 additions & 9 deletions Core/include/Acts/Propagator/TryAllNavigator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include "Acts/Surfaces/Surface.hpp"
#include "Acts/Utilities/Intersection.hpp"
#include "Acts/Utilities/Logger.hpp"
#include "Acts/Utilities/StringHelpers.hpp"

#include <algorithm>
#include <cstdint>
Expand Down Expand Up @@ -342,7 +343,9 @@ class TryAllNavigator : public TryAllNavigatorBase {
state.options.surfaceTolerance);
for (const auto& intersection : intersections.first.split()) {
// exclude invalid intersections
if (!detail::checkIntersection(intersection, nearLimit, farLimit)) {
if (!intersection.isValid() ||
!detail::checkPathLength(intersection.pathLength(), nearLimit,
farLimit)) {
continue;
}
// store candidate
Expand All @@ -357,6 +360,8 @@ class TryAllNavigator : public TryAllNavigatorBase {
ACTS_VERBOSE(volInfo(state) << "found " << intersectionCandidates.size()
<< " intersections");

bool intersectionFound = false;

for (const auto& candidate : intersectionCandidates) {
const auto& intersection = candidate.intersection;
const Surface& surface = *intersection.object();
Expand All @@ -375,13 +380,16 @@ class TryAllNavigator : public TryAllNavigatorBase {
continue;
}

ACTS_VERBOSE(volInfo(state) << "aiming at surface "
<< surface.geometryId() << ". step size is "
<< stepper.outputStepSize(state.stepping));
break;
if (surfaceStatus == IntersectionStatus::reachable) {
ACTS_VERBOSE(volInfo(state)
<< "Surface reachable, step size updated to "
<< stepper.outputStepSize(state.stepping));
intersectionFound = true;
break;
}
}

if (intersectionCandidates.empty()) {
if (!intersectionFound) {
stepper.releaseStepSize(state.stepping, ConstrainedStep::actor);

ACTS_VERBOSE(volInfo(state) << "no intersections found. advance without "
Expand Down Expand Up @@ -675,7 +683,8 @@ class TryAllOverstepNavigator : public TryAllNavigatorBase {
break;
}

ACTS_WARNING(volInfo(state) << "Surface unreachable, skip.");
ACTS_VERBOSE(volInfo(state) << "Surface " << surface.geometryId()
<< " unreachable, skip.");
++state.navigation.activeCandidateIndex;
}

Expand Down Expand Up @@ -738,8 +747,9 @@ class TryAllOverstepNavigator : public TryAllNavigatorBase {
state.geoContext, end, direction, state.options.surfaceTolerance);
for (const auto& intersection : intersections.first.split()) {
// exclude invalid intersections
if (!intersection ||
!detail::checkIntersection(intersection, nearLimit, farLimit)) {
if (!intersection.isValid() ||
!detail::checkPathLength(intersection.pathLength(), nearLimit,
farLimit)) {
continue;
}
// exclude last candidate
Expand Down
5 changes: 3 additions & 2 deletions Core/include/Acts/Propagator/detail/SteppingHelper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,9 @@ Acts::Intersection3D::Status updateSingleSurfaceStatus(
const double nearLimit = std::numeric_limits<double>::lowest();
const double farLimit = state.stepSize.value(ConstrainedStep::aborter);

if (sIntersection && detail::checkIntersection(sIntersection.intersection(),
nearLimit, farLimit, logger)) {
if (sIntersection.isValid() &&
detail::checkPathLength(sIntersection.pathLength(), nearLimit, farLimit,
logger)) {
ACTS_VERBOSE("Surface is reachable");
stepper.updateStepSize(state, sIntersection.pathLength(),
ConstrainedStep::actor);
Expand Down
8 changes: 3 additions & 5 deletions Core/include/Acts/TrackFinding/CombinatorialKalmanFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -272,9 +272,8 @@ struct CombinatorialKalmanFilterResult {
/// The Sequencer has to be part of the Navigator of the Propagator in order to
/// initialize and provide the measurement surfaces.
///
/// The Actor is part of the Propagation call and does the Kalman update and
/// eventually the smoothing. Updater and Calibrator are given to the Actor for
/// further use:
/// The Actor is part of the Propagation call and does the Kalman update.
/// Updater and Calibrator are given to the Actor for further use:
/// - The Updater is the implemented kalman updater formalism, it
/// runs via a visitor pattern through the measurements.
///
Expand Down Expand Up @@ -671,8 +670,7 @@ class CombinatorialKalmanFilter {
state.options.stepping.maxStepSize);

// Reset the navigation state
// Set targetSurface to nullptr for forward filtering; it's only needed
// after smoothing
// Set targetSurface to nullptr for forward filtering
auto navigationOptions = state.navigation.options;
navigationOptions.startSurface = &currentState.referenceSurface();
navigationOptions.targetSurface = nullptr;
Expand Down
5 changes: 4 additions & 1 deletion Core/include/Acts/TrackFitting/GainMatrixSmoother.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,16 @@ class GainMatrixSmoother {

/// Run the Kalman smoothing for one trajectory.
///
/// @param[in] gctx The geometry context to be used
/// @param[in,out] trajectory The trajectory to be smoothed
/// @param[in] entryIndex The index of state to start the smoothing
/// @param[in] logger Where to write logging information to
template <typename traj_t>
Result<void> operator()(const GeometryContext& /*gctx*/, traj_t& trajectory,
Result<void> operator()(const GeometryContext& gctx, traj_t& trajectory,
std::size_t entryIndex,
const Logger& logger = getDummyLogger()) const {
(void)gctx;

using TrackStateProxy = typename traj_t::TrackStateProxy;

GetParameters filtered;
Expand Down
32 changes: 13 additions & 19 deletions Core/include/Acts/TrackFitting/GainMatrixUpdater.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,13 @@ namespace Acts {
/// Kalman update step using the gain matrix formalism.
class GainMatrixUpdater {
struct InternalTrackState {
unsigned int calibratedSize;
// This is used to build a covariance matrix view in the .cpp file
const double* calibrated;
const double* calibratedCovariance;
TrackStateTraits<MultiTrajectoryTraits::MeasurementSizeMax,
false>::Projector projector;

TrackStateTraits<MultiTrajectoryTraits::MeasurementSizeMax,
false>::Parameters predicted;
TrackStateTraits<MultiTrajectoryTraits::MeasurementSizeMax,
Expand All @@ -32,12 +39,6 @@ class GainMatrixUpdater {
false>::Parameters filtered;
TrackStateTraits<MultiTrajectoryTraits::MeasurementSizeMax,
false>::Covariance filteredCovariance;
// This is used to build a covariance matrix view in the .cpp file
double* calibrated;
double* calibratedCovariance;
TrackStateTraits<MultiTrajectoryTraits::MeasurementSizeMax,
false>::Projector projector;
unsigned int calibratedSize;
};

public:
Expand Down Expand Up @@ -74,23 +75,16 @@ class GainMatrixUpdater {

auto [chi2, error] = visitMeasurement(
InternalTrackState{
trackState.calibratedSize(),
// Note that we pass raw pointers here which are used in the correct
// shape later
trackState.effectiveCalibrated().data(),
trackState.effectiveCalibratedCovariance().data(),
trackState.projector(),
trackState.predicted(),
trackState.predictedCovariance(),
trackState.filtered(),
trackState.filteredCovariance(),
// This abuses an incorrectly sized vector / matrix to access the
// data pointer! This works (don't use the matrix as is!), but be
// careful!
trackState
.template calibrated<
MultiTrajectoryTraits::MeasurementSizeMax>()
.data(),
trackState
.template calibratedCovariance<
MultiTrajectoryTraits::MeasurementSizeMax>()
.data(),
trackState.projector(),
trackState.calibratedSize(),
},
logger);

Expand Down
Loading

0 comments on commit f4e757f

Please sign in to comment.