Skip to content

Commit

Permalink
refactor!: converge to naming sourceLink (#3647)
Browse files Browse the repository at this point in the history
  • Loading branch information
AJPfleger authored Sep 25, 2024
1 parent 65aff94 commit 0d30307
Show file tree
Hide file tree
Showing 18 changed files with 81 additions and 83 deletions.
4 changes: 2 additions & 2 deletions Alignment/include/ActsAlignment/Kernel/Alignment.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ struct Alignment {
/// @tparam fit_options_t The fit options type
///
/// @param gctx The current geometry context object
/// @param sourcelinks The fittable uncalibrated measurements
/// @param sourceLinks The fittable uncalibrated measurements
/// @param sParameters The initial track parameters
/// @param fitOptions The fit Options steering the fit
/// @param idxedAlignSurfaces The idxed surfaces to be aligned
Expand All @@ -161,7 +161,7 @@ struct Alignment {
typename fit_options_t>
Acts::Result<detail::TrackAlignmentState> evaluateTrackAlignmentState(
const Acts::GeometryContext& gctx,
const std::vector<source_link_t>& sourcelinks,
const std::vector<source_link_t>& sourceLinks,
const start_parameters_t& sParameters, const fit_options_t& fitOptions,
const std::unordered_map<const Acts::Surface*, std::size_t>&
idxedAlignSurfaces,
Expand Down
10 changes: 5 additions & 5 deletions Alignment/include/ActsAlignment/Kernel/Alignment.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ template <typename source_link_t, typename start_parameters_t,
Acts::Result<ActsAlignment::detail::TrackAlignmentState>
ActsAlignment::Alignment<fitter_t>::evaluateTrackAlignmentState(
const Acts::GeometryContext& gctx,
const std::vector<source_link_t>& sourcelinks,
const std::vector<source_link_t>& sourceLinks,
const start_parameters_t& sParameters, const fit_options_t& fitOptions,
const std::unordered_map<const Acts::Surface*, std::size_t>&
idxedAlignSurfaces,
Expand All @@ -24,8 +24,8 @@ ActsAlignment::Alignment<fitter_t>::evaluateTrackAlignmentState(
Acts::VectorMultiTrajectory{}};

// Convert to Acts::SourceLink during iteration
Acts::SourceLinkAdapterIterator begin{sourcelinks.begin()};
Acts::SourceLinkAdapterIterator end{sourcelinks.end()};
Acts::SourceLinkAdapterIterator begin{sourceLinks.begin()};
Acts::SourceLinkAdapterIterator end{sourceLinks.end()};

// Perform the fit
auto fitRes = m_fitter.fit(begin, end, sParameters, fitOptions, tracks);
Expand Down Expand Up @@ -82,13 +82,13 @@ void ActsAlignment::Alignment<fitter_t>::calculateAlignmentParameters(
alignResult.numTracks = trajectoryCollection.size();
double sumChi2ONdf = 0;
for (unsigned int iTraj = 0; iTraj < trajectoryCollection.size(); iTraj++) {
const auto& sourcelinks = trajectoryCollection.at(iTraj);
const auto& sourceLinks = trajectoryCollection.at(iTraj);
const auto& sParameters = startParametersCollection.at(iTraj);
// Set the target surface
fitOptionsWithRefSurface.referenceSurface = &sParameters.referenceSurface();
// The result for one single track
auto evaluateRes = evaluateTrackAlignmentState(
fitOptions.geoContext, sourcelinks, sParameters,
fitOptions.geoContext, sourceLinks, sParameters,
fitOptionsWithRefSurface, alignResult.idxedAlignSurfaces, alignMask);
if (!evaluateRes.ok()) {
ACTS_DEBUG("Evaluation of alignment state for track " << iTraj
Expand Down
2 changes: 1 addition & 1 deletion Core/include/Acts/EventData/SourceLink.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ class SourceLink final {
SourceLink& operator=(const SourceLink& other) = default;
SourceLink& operator=(SourceLink&& other) = default;

/// Constructor from concrete sourcelink
/// Constructor from concrete source link
/// @tparam T The source link type
/// @param upstream The upstream source link to store
template <typename T>
Expand Down
10 changes: 5 additions & 5 deletions Core/include/Acts/EventData/VectorMultiTrajectory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,8 +157,8 @@ class VectorMultiTrajectoryBase {
double pathLength = 0;
TrackStateType::raw_type typeFlags{};

IndexType iuncalibrated = kInvalid;
IndexType icalibratedsourcelink = kInvalid;
IndexType iUncalibrated = kInvalid;
IndexType iCalibratedSourceLink = kInvalid;
IndexType measdim = kInvalid;

TrackStatePropMask allocMask = TrackStatePropMask::None;
Expand Down Expand Up @@ -209,7 +209,7 @@ class VectorMultiTrajectoryBase {
case "projector"_hash:
return instance.m_index[istate].iprojector != kInvalid;
case "uncalibratedSourceLink"_hash:
return instance.m_sourceLinks[instance.m_index[istate].iuncalibrated]
return instance.m_sourceLinks[instance.m_index[istate].iUncalibrated]
.has_value();
case "previous"_hash:
case "next"_hash:
Expand Down Expand Up @@ -304,7 +304,7 @@ class VectorMultiTrajectoryBase {
}

SourceLink getUncalibratedSourceLink_impl(IndexType istate) const {
return m_sourceLinks[m_index[istate].iuncalibrated].value();
return m_sourceLinks[m_index[istate].iUncalibrated].value();
}

const Surface* referenceSurface_impl(IndexType istate) const {
Expand Down Expand Up @@ -485,7 +485,7 @@ class VectorMultiTrajectory final

void setUncalibratedSourceLink_impl(IndexType istate,
SourceLink&& sourceLink) {
m_sourceLinks[m_index[istate].iuncalibrated] = std::move(sourceLink);
m_sourceLinks[m_index[istate].iUncalibrated] = std::move(sourceLink);
}

void setReferenceSurface_impl(IndexType istate,
Expand Down
27 changes: 13 additions & 14 deletions Core/include/Acts/TrackFinding/CombinatorialKalmanFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ struct CombinatorialKalmanFilterOptions {
: geoContext(gctx),
magFieldContext(mctx),
calibrationContext(cctx),
sourcelinkAccessor(std::move(accessor_)),
sourceLinkAccessor(std::move(accessor_)),
extensions(extensions_),
propagatorPlainOptions(pOptions),
multipleScattering(mScattering),
Expand All @@ -182,7 +182,7 @@ struct CombinatorialKalmanFilterOptions {
std::reference_wrapper<const CalibrationContext> calibrationContext;

/// The source link accessor
SourceLinkAccessor sourcelinkAccessor;
SourceLinkAccessor sourceLinkAccessor;

/// The filter extensions
CombinatorialKalmanFilterExtensions<track_container_t> extensions;
Expand All @@ -199,7 +199,7 @@ struct CombinatorialKalmanFilterOptions {

/// Delegate definition to create track states for selected measurements
///
/// @note expected to iterator over the given sourcelink range,
/// @note expected to iterator over the given sourceLink range,
/// select measurements, and create track states for
/// which new tips are to be created, more over the outlier
/// flag should be set for states that are outlier.
Expand All @@ -208,8 +208,8 @@ struct CombinatorialKalmanFilterOptions {
/// @param calibrationContext pointer to the current calibration context
/// @param surface the surface at which new track states are to be created
/// @param boundState the current bound state of the trajectory
/// @param slBegin Begin iterator for sourcelinks
/// @param slEnd End iterator for sourcelinks
/// @param slBegin Begin iterator for sourceLinks
/// @param slEnd End iterator for sourceLinks
/// @param prevTip Index pointing at previous trajectory state (i.e. tip)
/// @param bufferTrajectory a temporary trajectory which can be used to create temporary track states
/// @param trackStateCandidates a temporary buffer that can be used to collect track states
Expand Down Expand Up @@ -332,8 +332,8 @@ class CombinatorialKalmanFilter {
/// @param calibrationContext pointer to the current calibration context
/// @param surface the surface the sourceLinks are associated to
/// @param boundState Bound state from the propagation on this surface
/// @param slBegin Begin iterator for sourcelinks
/// @param slEnd End iterator for sourcelinks
/// @param slBegin Begin iterator for sourceLinks
/// @param slEnd End iterator for sourceLinks
/// @param prevTip Index pointing at previous trajectory state (i.e. tip)
/// @param bufferTrajectory a buffer for temporary candidate track states
/// @param trackStateCandidates a buffer for temporary track state proxies for candidates
Expand Down Expand Up @@ -725,7 +725,7 @@ class CombinatorialKalmanFilter {

std::size_t nBranchesOnSurface = 0;

if (auto [slBegin, slEnd] = m_sourcelinkAccessor(*surface);
if (auto [slBegin, slEnd] = m_sourceLinkAccessor(*surface);
slBegin != slEnd) {
// Screen output message
ACTS_VERBOSE("Measurement surface " << surface->geometryId()
Expand Down Expand Up @@ -1175,17 +1175,16 @@ class CombinatorialKalmanFilter {
CombinatorialKalmanFilterExtensions<track_container_t> m_extensions;

/// The source link accessor
source_link_accessor_t m_sourcelinkAccessor;
source_link_accessor_t m_sourceLinkAccessor;

using source_link_iterator_t =
decltype(std::declval<decltype(m_sourcelinkAccessor(
using SourceLinkIterator =
decltype(std::declval<decltype(m_sourceLinkAccessor(
*static_cast<const Surface*>(nullptr)))>()
.first);

using TrackStateCandidateCreator =
typename CombinatorialKalmanFilterOptions<
source_link_iterator_t,
track_container_t>::TrackStateCandidateCreator;
SourceLinkIterator, track_container_t>::TrackStateCandidateCreator;

/// the stateCandidator to be used
/// @note will be set to a default trackStateCandidateCreator or the one
Expand Down Expand Up @@ -1274,7 +1273,7 @@ class CombinatorialKalmanFilter {
combKalmanActor.calibrationContextPtr = &tfOptions.calibrationContext.get();

// copy source link accessor, calibrator and measurement selector
combKalmanActor.m_sourcelinkAccessor = tfOptions.sourcelinkAccessor;
combKalmanActor.m_sourceLinkAccessor = tfOptions.sourceLinkAccessor;
combKalmanActor.m_extensions = tfOptions.extensions;
combKalmanActor.trackStateCandidateCreator =
tfOptions.trackStateCandidateCreator;
Expand Down
6 changes: 3 additions & 3 deletions Core/include/Acts/TrackFitting/GlobalChiSquareFitter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -689,8 +689,8 @@ class Gx2Fitter {
}

// Here we handle all measurements
if (auto sourcelink_it = inputMeasurements->find(geoId);
sourcelink_it != inputMeasurements->end()) {
if (auto sourceLinkIt = inputMeasurements->find(geoId);
sourceLinkIt != inputMeasurements->end()) {
ACTS_DEBUG(" The surface contains a measurement.");

// Transport the covariance to the surface
Expand Down Expand Up @@ -755,7 +755,7 @@ class Gx2Fitter {
// We have smoothed parameters, so calibrate the uncalibrated input
// measurement
extensions.calibrator(state.geoContext, *calibrationContext,
sourcelink_it->second, trackStateProxy);
sourceLinkIt->second, trackStateProxy);

// Get and set the type flags
auto typeFlags = trackStateProxy.typeFlags();
Expand Down
14 changes: 7 additions & 7 deletions Core/include/Acts/TrackFitting/KalmanFitter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -591,8 +591,8 @@ class KalmanFitter {
const stepper_t& stepper, const navigator_t& navigator,
result_type& result) const {
// Try to find the surface in the measurement surfaces
auto sourcelink_it = inputMeasurements->find(surface->geometryId());
if (sourcelink_it != inputMeasurements->end()) {
auto sourceLinkIt = inputMeasurements->find(surface->geometryId());
if (sourceLinkIt != inputMeasurements->end()) {
// Screen output message
ACTS_VERBOSE("Measurement surface " << surface->geometryId()
<< " detected.");
Expand All @@ -608,7 +608,7 @@ class KalmanFitter {
// point in performing globalToLocal correction)
auto trackStateProxyRes = detail::kalmanHandleMeasurement(
*calibrationContext, state, stepper, extensions, *surface,
sourcelink_it->second, *result.fittedStates, result.lastTrackIndex,
sourceLinkIt->second, *result.fittedStates, result.lastTrackIndex,
false, logger());

if (!trackStateProxyRes.ok()) {
Expand Down Expand Up @@ -699,8 +699,8 @@ class KalmanFitter {
const navigator_t& navigator,
result_type& result) const {
// Try to find the surface in the measurement surfaces
auto sourcelink_it = inputMeasurements->find(surface->geometryId());
if (sourcelink_it != inputMeasurements->end()) {
auto sourceLinkIt = inputMeasurements->find(surface->geometryId());
if (sourceLinkIt != inputMeasurements->end()) {
// Screen output message
ACTS_VERBOSE("Measurement surface "
<< surface->geometryId()
Expand Down Expand Up @@ -761,7 +761,7 @@ class KalmanFitter {
// We have predicted parameters, so calibrate the uncalibrated input
// measurement
extensions.calibrator(state.geoContext, *calibrationContext,
sourcelink_it->second, trackStateProxy);
sourceLinkIt->second, trackStateProxy);

// If the update is successful, set covariance and
auto updateRes =
Expand Down Expand Up @@ -1084,7 +1084,7 @@ class KalmanFitter {
ACTS_VERBOSE("Preparing " << std::distance(it, end)
<< " input measurements");
std::map<GeometryIdentifier, SourceLink> inputMeasurements;
// for (const auto& sl : sourcelinks) {
// for (const auto& sl : sourceLinks) {
for (; it != end; ++it) {
SourceLink sl = *it;
const Surface* surface = kfOptions.extensions.surfaceAccessor(sl);
Expand Down
12 changes: 6 additions & 6 deletions Core/include/Acts/TrackFitting/detail/GsfActor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,13 +206,13 @@ struct GsfActor {
result.visitedSurfaces.push_back(&surface);

// Check what we have on this surface
const auto found_source_link =
const auto foundSourceLink =
m_cfg.inputMeasurements->find(surface.geometryId());
const bool haveMaterial =
navigator.currentSurface(state.navigation)->surfaceMaterial() &&
!m_cfg.disableAllMaterialHandling;
const bool haveMeasurement =
found_source_link != m_cfg.inputMeasurements->end();
foundSourceLink != m_cfg.inputMeasurements->end();

ACTS_VERBOSE(std::boolalpha << "haveMaterial " << haveMaterial
<< ", haveMeasurement: " << haveMeasurement);
Expand Down Expand Up @@ -263,7 +263,7 @@ struct GsfActor {
TemporaryStates tmpStates;

auto res = kalmanUpdate(state, stepper, navigator, result, tmpStates,
found_source_link->second);
foundSourceLink->second);

if (!res.ok()) {
setErrorOrAbort(res.error());
Expand All @@ -281,7 +281,7 @@ struct GsfActor {

if (haveMeasurement) {
res = kalmanUpdate(state, stepper, navigator, result, tmpStates,
found_source_link->second);
foundSourceLink->second);
} else {
res = noMeasurementUpdate(state, stepper, navigator, result, tmpStates,
false);
Expand Down Expand Up @@ -547,7 +547,7 @@ struct GsfActor {
Result<void> kalmanUpdate(propagator_state_t& state, const stepper_t& stepper,
const navigator_t& navigator, result_type& result,
TemporaryStates& tmpStates,
const SourceLink& source_link) const {
const SourceLink& sourceLink) const {
const auto& surface = *navigator.currentSurface(state.navigation);

// Boolean flag, to distinguish measurement and outlier states. This flag
Expand All @@ -563,7 +563,7 @@ struct GsfActor {

auto trackStateProxyRes = detail::kalmanHandleMeasurement(
*m_cfg.calibrationContext, singleState, singleStepper,
m_cfg.extensions, surface, source_link, tmpStates.traj,
m_cfg.extensions, surface, sourceLink, tmpStates.traj,
MultiTrajectoryTraits::kInvalid, false, logger());

if (!trackStateProxyRes.ok()) {
Expand Down
6 changes: 3 additions & 3 deletions Core/include/Acts/TrackFitting/detail/KalmanUpdateHelpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace Acts::detail {
/// @param stepper The stepper
/// @param extensions The extension used for the update
/// @param surface The current surface
/// @param source_link The source-link used for the update
/// @param sourceLink The source link used for the update
/// @param fittedStates The Multitrajectory to that we add the state
/// @param lastTrackIndex The parent index for the new state in the MT
/// @param doCovTransport Whether to perform a covariance transport when
Expand All @@ -38,7 +38,7 @@ template <typename propagator_state_t, typename stepper_t,
auto kalmanHandleMeasurement(
const CalibrationContext &calibrationContext, propagator_state_t &state,
const stepper_t &stepper, const extensions_t &extensions,
const Surface &surface, const SourceLink &source_link, traj_t &fittedStates,
const Surface &surface, const SourceLink &sourceLink, traj_t &fittedStates,
const std::size_t lastTrackIndex, bool doCovTransport, const Logger &logger,
const FreeToBoundCorrection &freeToBoundCorrection = FreeToBoundCorrection(
false)) -> Result<typename traj_t::TrackStateProxy> {
Expand Down Expand Up @@ -75,7 +75,7 @@ auto kalmanHandleMeasurement(

// We have predicted parameters, so calibrate the uncalibrated input
// measurement
extensions.calibrator(state.geoContext, calibrationContext, source_link,
extensions.calibrator(state.geoContext, calibrationContext, sourceLink,
trackStateProxy);

// Get and set the type flags
Expand Down
6 changes: 3 additions & 3 deletions Core/src/EventData/VectorMultiTrajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,14 +67,14 @@ auto VectorMultiTrajectory::addTrackState_impl(
}

m_sourceLinks.emplace_back(std::nullopt);
p.iuncalibrated = m_sourceLinks.size() - 1;
p.iUncalibrated = m_sourceLinks.size() - 1;

m_measOffset.push_back(kInvalid);
m_measCovOffset.push_back(kInvalid);

if (ACTS_CHECK_BIT(mask, PropMask::Calibrated)) {
m_sourceLinks.emplace_back(std::nullopt);
p.icalibratedsourcelink = m_sourceLinks.size() - 1;
p.iCalibratedSourceLink = m_sourceLinks.size() - 1;

m_projectors.push_back(0);
p.iprojector = m_projectors.size() - 1;
Expand Down Expand Up @@ -129,7 +129,7 @@ void VectorMultiTrajectory::addTrackStateComponents_impl(
if (ACTS_CHECK_BIT(mask, PropMask::Calibrated) &&
!ACTS_CHECK_BIT(currentMask, PropMask::Calibrated)) {
m_sourceLinks.emplace_back(std::nullopt);
p.icalibratedsourcelink = m_sourceLinks.size() - 1;
p.iCalibratedSourceLink = m_sourceLinks.size() - 1;

m_projectors.push_back(0);
p.iprojector = m_projectors.size() - 1;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ class TrackFindingAlgorithm final : public IAlgorithm {

private:
template <typename source_link_accessor_container_t>
void computeSharedHits(const source_link_accessor_container_t& sourcelinks,
void computeSharedHits(const source_link_accessor_container_t& sourceLinks,
TrackContainer& tracks) const;

ActsExamples::ProcessCode finalize() override;
Expand Down
13 changes: 6 additions & 7 deletions Examples/Algorithms/TrackFinding/src/GbtsSeedingAlgorithm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -197,19 +197,18 @@ ActsExamples::GbtsSeedingAlgorithm::MakeGbtsSpacePoints(

// Gbts space point vector
// loop over space points, call on map
const auto &source_link = spacePoint.sourceLinks();
const auto &index_source_link =
source_link.front().get<IndexSourceLink>();
const auto &sourceLink = spacePoint.sourceLinks();
const auto &indexSourceLink = sourceLink.front().get<IndexSourceLink>();

// warning if source link empty
if (source_link.empty()) {
if (sourceLink.empty()) {
// warning in officaial acts format
ACTS_WARNING("warning source link vector is empty");
continue;
}
int ACTS_vol_id = index_source_link.geometryId().volume();
int ACTS_lay_id = index_source_link.geometryId().layer();
int ACTS_mod_id = index_source_link.geometryId().sensitive();
int ACTS_vol_id = indexSourceLink.geometryId().volume();
int ACTS_lay_id = indexSourceLink.geometryId().layer();
int ACTS_mod_id = indexSourceLink.geometryId().sensitive();

// dont want strips or HGTD
if (ACTS_vol_id == 2 || ACTS_vol_id == 22 || ACTS_vol_id == 23 ||
Expand Down
Loading

0 comments on commit 0d30307

Please sign in to comment.