Skip to content

Commit

Permalink
refactor: Remove LoggerWrapper in favor of Logger refs (#1812)
Browse files Browse the repository at this point in the history
To harmonize / simplify the ways that loggers are used, this PR removes `LoggerWrapper`. To support the case of e.g. functions optionally accepting a logger, we can use `const Logger&` and default it to `getDummyLogger`. Since `getDummyLogger` returns a reference to a logger instance of static lifetime, all the arguments should be safe, even if they are retained (I think).
  • Loading branch information
paulgessinger committed Feb 1, 2023
1 parent 0e3a9e4 commit 38926ae
Show file tree
Hide file tree
Showing 51 changed files with 227 additions and 286 deletions.
26 changes: 12 additions & 14 deletions Alignment/include/ActsAlignment/Kernel/Alignment.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,6 @@ struct AlignmentOptions {
/// AlignmentOptions
///
/// @param fOptions The fit options
/// @param logger_ The logger wrapper
/// @param aTransformUpdater The updater to update aligned transform
/// @param aDetElements The alignable detector elements
/// @param chi2CufOff The alignment chi2 tolerance
Expand All @@ -53,7 +52,6 @@ struct AlignmentOptions {
AlignmentOptions(
const fit_options_t& fOptions,
const AlignedTransformUpdater& aTransformUpdater,
Acts::LoggerWrapper logger_,
const std::vector<Acts::DetectorElementBase*>& aDetElements = {},
double chi2CutOff = 0.5,
const std::pair<size_t, double>& deltaChi2CutOff = {5, 0.01},
Expand All @@ -65,8 +63,7 @@ struct AlignmentOptions {
averageChi2ONdfCutOff(chi2CutOff),
deltaAverageChi2ONdfCutOff(deltaChi2CutOff),
maxIterations(maxIters),
iterationState(iterState),
logger(logger_) {}
iterationState(iterState) {}

// The fit options
fit_options_t fitOptions;
Expand All @@ -89,9 +86,6 @@ struct AlignmentOptions {

// The alignment mask for different iterations
std::map<unsigned int, AlignmentMask> iterationState;

/// Logger
Acts::LoggerWrapper logger;
};

/// @brief Alignment result struct
Expand Down Expand Up @@ -142,7 +136,10 @@ struct Alignment {
Alignment() = delete;

/// Constructor from arguments
Alignment(fitter_t fitter) : m_fitter(std::move(fitter)) {}
Alignment(fitter_t fitter,
std::unique_ptr<const Acts::Logger> _logger =
Acts::getDefaultLogger("Alignment", Acts::Logging::INFO))
: m_fitter(std::move(fitter)), m_logger{std::move(_logger)} {}

/// @brief evaluate alignment state for a single track
///
Expand All @@ -168,8 +165,7 @@ struct Alignment {
const start_parameters_t& sParameters, const fit_options_t& fitOptions,
const std::unordered_map<const Acts::Surface*, size_t>&
idxedAlignSurfaces,
const AlignmentMask& alignMask,
Acts::LoggerWrapper logger = Acts::getDummyLogger()) const;
const AlignmentMask& alignMask) const;

/// @brief calculate the alignment parameters delta
///
Expand All @@ -190,8 +186,7 @@ struct Alignment {
const trajectory_container_t& trajectoryCollection,
const start_parameters_container_t& startParametersCollection,
const fit_options_t& fitOptions, AlignmentResult& alignResult,
const AlignmentMask& alignMask = AlignmentMask::All,
Acts::LoggerWrapper logger = Acts::getDummyLogger()) const;
const AlignmentMask& alignMask = AlignmentMask::All) const;

/// @brief update the detector element alignment parameters
///
Expand All @@ -203,8 +198,7 @@ struct Alignment {
const Acts::GeometryContext& gctx,
const std::vector<Acts::DetectorElementBase*>& alignedDetElements,
const AlignedTransformUpdater& alignedTransformUpdater,
AlignmentResult& alignResult,
Acts::LoggerWrapper logger = Acts::getDummyLogger()) const;
AlignmentResult& alignResult) const;

/// @brief Alignment implementation
///
Expand All @@ -229,6 +223,10 @@ struct Alignment {
private:
// The fitter
fitter_t m_fitter;

std::unique_ptr<const Acts::Logger> m_logger;

const Acts::Logger& logger() const { return *m_logger; }
};
} // namespace ActsAlignment

Expand Down
18 changes: 6 additions & 12 deletions Alignment/include/ActsAlignment/Kernel/Alignment.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,7 @@ ActsAlignment::Alignment<fitter_t>::evaluateTrackAlignmentState(
const std::vector<source_link_t>& sourcelinks,
const start_parameters_t& sParameters, const fit_options_t& fitOptions,
const std::unordered_map<const Acts::Surface*, size_t>& idxedAlignSurfaces,
const ActsAlignment::AlignmentMask& alignMask,
Acts::LoggerWrapper logger) const {
const ActsAlignment::AlignmentMask& alignMask) const {
Acts::TrackContainer tracks{Acts::VectorTrackContainer{},
Acts::VectorMultiTrajectory{}};

Expand Down Expand Up @@ -59,8 +58,7 @@ void ActsAlignment::Alignment<fitter_t>::calculateAlignmentParameters(
const start_parameters_container_t& startParametersCollection,
const fit_options_t& fitOptions,
ActsAlignment::AlignmentResult& alignResult,
const ActsAlignment::AlignmentMask& alignMask,
Acts::LoggerWrapper logger) const {
const ActsAlignment::AlignmentMask& alignMask) const {
// The number of trajectories must be eual to the number of starting
// parameters
assert(trajectoryCollection.size() == startParametersCollection.size());
Expand Down Expand Up @@ -90,8 +88,7 @@ void ActsAlignment::Alignment<fitter_t>::calculateAlignmentParameters(
// The result for one single track
auto evaluateRes = evaluateTrackAlignmentState(
fitOptions.geoContext, sourcelinks, sParameters,
fitOptionsWithRefSurface, alignResult.idxedAlignSurfaces, alignMask,
logger);
fitOptionsWithRefSurface, alignResult.idxedAlignSurfaces, alignMask);
if (not evaluateRes.ok()) {
ACTS_DEBUG("Evaluation of alignment state for track " << iTraj
<< " failed");
Expand Down Expand Up @@ -159,8 +156,7 @@ ActsAlignment::Alignment<fitter_t>::updateAlignmentParameters(
const Acts::GeometryContext& gctx,
const std::vector<Acts::DetectorElementBase*>& alignedDetElements,
const ActsAlignment::AlignedTransformUpdater& alignedTransformUpdater,
ActsAlignment::AlignmentResult& alignResult,
Acts::LoggerWrapper logger) const {
ActsAlignment::AlignmentResult& alignResult) const {
// Update the aligned transform
Acts::AlignmentVector deltaAlignmentParam = Acts::AlignmentVector::Zero();
for (const auto& [surface, index] : alignResult.idxedAlignSurfaces) {
Expand Down Expand Up @@ -221,8 +217,6 @@ ActsAlignment::Alignment<fitter_t>::align(
const trajectory_container_t& trajectoryCollection,
const start_parameters_container_t& startParametersCollection,
const ActsAlignment::AlignmentOptions<fit_options_t>& alignOptions) const {
const auto& logger = alignOptions.logger;

// Construct an AlignmentResult object
AlignmentResult alignResult;

Expand Down Expand Up @@ -253,7 +247,7 @@ ActsAlignment::Alignment<fitter_t>::align(
// Calculate the alignment parameters delta etc.
calculateAlignmentParameters(
trajectoryCollection, startParametersCollection,
alignOptions.fitOptions, alignResult, alignMask, logger);
alignOptions.fitOptions, alignResult, alignMask);
// Screen out the information
ACTS_INFO("iIter = " << iIter << ", total chi2 = " << alignResult.chi2
<< ", total measurementDim = "
Expand Down Expand Up @@ -294,7 +288,7 @@ ActsAlignment::Alignment<fitter_t>::align(
// Not coveraged yet, update the detector element alignment parameters
auto updateRes = updateAlignmentParameters(
alignOptions.fitOptions.geoContext, alignOptions.alignedDetElements,
alignOptions.alignedTransformUpdater, alignResult, logger);
alignOptions.alignedTransformUpdater, alignResult);
if (not updateRes.ok()) {
ACTS_ERROR("Update alignment parameters failed: " << updateRes.error());
return updateRes.error();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ struct CorrectedFreeToBoundTransformer {
const FreeVector& freeParams, const FreeSymMatrix& freeCovariance,
const Surface& surface, const GeometryContext& geoContext,
NavigationDirection navDir = NavigationDirection::Forward,
LoggerWrapper logger = getDummyLogger()) const;
const Logger& logger = getDummyLogger()) const;

private:
/// The parameters to tune the weight in UKF (0 < alpha <=1)
Expand Down
2 changes: 1 addition & 1 deletion Core/include/Acts/Propagator/AtlasStepper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -381,7 +381,7 @@ class AtlasStepper {
/// @param [in] logger Logger instance to use
Intersection3D::Status updateSurfaceStatus(
State& state, const Surface& surface, const BoundaryCheck& bcheck,
LoggerWrapper logger = getDummyLogger()) const {
const Logger& logger = getDummyLogger()) const {
return detail::updateSingleSurfaceStatus<AtlasStepper>(
*this, state, surface, bcheck, logger);
}
Expand Down
4 changes: 2 additions & 2 deletions Core/include/Acts/Propagator/EigenStepper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,10 +238,10 @@ class EigenStepper {
/// @param [in,out] state The stepping state (thread-local cache)
/// @param [in] surface The surface provided
/// @param [in] bcheck The boundary check for this status update
/// @param [in] logger A @c LoggerWrapper instance
/// @param [in] logger A @c Logger instance
Intersection3D::Status updateSurfaceStatus(
State& state, const Surface& surface, const BoundaryCheck& bcheck,
LoggerWrapper logger = getDummyLogger()) const {
const Logger& logger = getDummyLogger()) const {
return detail::updateSingleSurfaceStatus<EigenStepper>(
*this, state, surface, bcheck, logger);
}
Expand Down
4 changes: 2 additions & 2 deletions Core/include/Acts/Propagator/MultiEigenStepperLoop.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -617,10 +617,10 @@ class MultiEigenStepperLoop
/// @param state [in,out] The stepping state (thread-local cache)
/// @param surface [in] The surface provided
/// @param bcheck [in] The boundary check for this status update
/// @param logger [in] A @c LoggerWrapper instance
/// @param logger [in] A @c Loggerinstance
Intersection3D::Status updateSurfaceStatus(
State& state, const Surface& surface, const BoundaryCheck& bcheck,
LoggerWrapper logger = getDummyLogger()) const {
const Logger& logger = getDummyLogger()) const {
using Status = Intersection3D::Status;

std::array<int, 4> counts = {0, 0, 0, 0};
Expand Down
2 changes: 1 addition & 1 deletion Core/include/Acts/Propagator/StepperConcept.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ constexpr bool MultiStepperStateConcept= require<
constexpr static bool covariance_transport_exists = require<has_method<const S, void, covariance_transport_curvilinear_t, state&>,
has_method<const S, void, covariance_transport_bound_t, state&, const Surface&, const FreeToBoundCorrection&>>;
static_assert(covariance_transport_exists, "covarianceTransport method not found");
constexpr static bool update_surface_exists = has_method<const S, Intersection3D::Status, update_surface_status_t, state&, const Surface&, const BoundaryCheck&, LoggerWrapper>;
constexpr static bool update_surface_exists = has_method<const S, Intersection3D::Status, update_surface_status_t, state&, const Surface&, const BoundaryCheck&, const Logger&>;
static_assert(update_surface_exists, "updateSurfaceStatus method not found");
constexpr static bool set_step_size_exists = has_method<const S, void, set_step_size_t, state&, double, ConstrainedStep::Type, bool>;
static_assert(set_step_size_exists, "setStepSize method not found");
Expand Down
2 changes: 1 addition & 1 deletion Core/include/Acts/Propagator/StraightLineStepper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ class StraightLineStepper {
/// @param [in] logger A logger instance
Intersection3D::Status updateSurfaceStatus(
State& state, const Surface& surface, const BoundaryCheck& bcheck,
LoggerWrapper logger = getDummyLogger()) const {
const Logger& logger = getDummyLogger()) const {
return detail::updateSingleSurfaceStatus<StraightLineStepper>(
*this, state, surface, bcheck, logger);
}
Expand Down
2 changes: 1 addition & 1 deletion Core/include/Acts/Propagator/detail/SteppingHelper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ namespace detail {
template <typename stepper_t>
Acts::Intersection3D::Status updateSingleSurfaceStatus(
const stepper_t& stepper, typename stepper_t::State& state,
const Surface& surface, const BoundaryCheck& bcheck, LoggerWrapper logger) {
const Surface& surface, const BoundaryCheck& bcheck, const Logger& logger) {
ACTS_VERBOSE(
"Update single surface status for surface: " << surface.geometryId());

Expand Down
2 changes: 1 addition & 1 deletion Core/include/Acts/TrackFinding/MeasurementSelector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -198,7 +198,7 @@ class MeasurementSelector {
static cut_value_t VariableCut(
const typename Acts::MultiTrajectory<traj_t>::TrackStateProxy& trackState,
const Acts::MeasurementSelector::Config::Iterator selector,
const std::vector<cut_value_t>& cuts, LoggerWrapper logger) {
const std::vector<cut_value_t>& cuts, const Logger& logger) {
const auto& etaBins = selector->etaBins;
if (etaBins.empty()) {
return cuts[0]; // shortcut if no etaBins
Expand Down
4 changes: 2 additions & 2 deletions Core/include/Acts/TrackFitting/GainMatrixSmoother.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ class GainMatrixSmoother {
template <typename D>
Result<void> operator()(const GeometryContext& gctx,
MultiTrajectory<D>& trajectory, size_t entryIndex,
LoggerWrapper logger = getDummyLogger()) const {
const Logger& logger = getDummyLogger()) const {
(void)gctx;

using TrackStateProxy = typename MultiTrajectory<D>::TrackStateProxy;
Expand Down Expand Up @@ -136,7 +136,7 @@ class GainMatrixSmoother {
const GetCovariance& predictedCovariance,
const GetCovariance& smoothedCovariance,
const GetCovariance& jacobian,
LoggerWrapper logger) const;
const Logger& logger) const;
};

} // namespace Acts
4 changes: 2 additions & 2 deletions Core/include/Acts/TrackFitting/GainMatrixUpdater.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class GainMatrixUpdater {
const GeometryContext& gctx,
typename MultiTrajectory<traj_t>::TrackStateProxy trackState,
NavigationDirection direction = NavigationDirection::Forward,
LoggerWrapper logger = getDummyLogger()) const {
const Logger& logger = getDummyLogger()) const {
(void)gctx;
ACTS_VERBOSE("Invoked GainMatrixUpdater");

Expand Down Expand Up @@ -104,7 +104,7 @@ class GainMatrixUpdater {
private:
std::tuple<double, std::error_code> visitMeasurement(
InternalTrackState trackState, NavigationDirection direction,
LoggerWrapper logger) const;
const Logger& logger) const;
};

} // namespace Acts
4 changes: 1 addition & 3 deletions Core/include/Acts/TrackFitting/GsfOptions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ struct GsfExtensions {
using Calibrator = Delegate<void(const GeometryContext&, TrackStateProxy)>;

using Updater = Delegate<Result<void>(const GeometryContext&, TrackStateProxy,
NavigationDirection, LoggerWrapper)>;
NavigationDirection, const Logger&)>;

using OutlierFinder = Delegate<bool(ConstTrackStateProxy)>;

Expand Down Expand Up @@ -62,8 +62,6 @@ struct GsfOptions {

GsfExtensions<traj_t> extensions;

LoggerWrapper logger;

PropagatorPlainOptions propagatorPlainOptions;

const Surface* referenceSurface = nullptr;
Expand Down
4 changes: 2 additions & 2 deletions Core/include/Acts/TrackFitting/KalmanFitter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,10 +55,10 @@ struct KalmanFitterExtensions {
using Calibrator = Delegate<void(const GeometryContext&, TrackStateProxy)>;

using Smoother = Delegate<Result<void>(
const GeometryContext&, MultiTrajectory<traj_t>&, size_t, LoggerWrapper)>;
const GeometryContext&, MultiTrajectory<traj_t>&, size_t, const Logger&)>;

using Updater = Delegate<Result<void>(const GeometryContext&, TrackStateProxy,
NavigationDirection, LoggerWrapper)>;
NavigationDirection, const Logger&)>;

using OutlierFinder = Delegate<bool(ConstTrackStateProxy)>;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ template <typename traj_t>
Result<void> voidKalmanUpdater(
const GeometryContext& /*gctx*/,
typename MultiTrajectory<traj_t>::TrackStateProxy trackState,
NavigationDirection /*direction*/, LoggerWrapper /*logger*/) {
NavigationDirection /*direction*/, const Logger& /*logger*/) {
trackState.filtered() = trackState.predicted();
trackState.filteredCovariance() = trackState.predictedCovariance();
return Result<void>::success();
Expand All @@ -36,7 +36,7 @@ Result<void> voidKalmanUpdater(
template <typename traj_t>
Result<void> voidKalmanSmoother(const GeometryContext& /*gctx*/,
MultiTrajectory<traj_t>& trackStates,
size_t entry, LoggerWrapper /*logger*/) {
size_t entry, const Logger& /*logger*/) {
trackStates.applyBackwards(entry, [](auto trackState) {
trackState.smoothed() = trackState.filtered();
trackState.smoothedCovariance() = trackState.filteredCovariance();
Expand Down
38 changes: 16 additions & 22 deletions Core/include/Acts/Utilities/Intersection.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -198,36 +198,30 @@ namespace detail {
template <typename intersection_t, typename logger_t = std::false_type>
bool checkIntersection(const intersection_t& intersection, double pLimit,
double oLimit, double tolerance,
[[maybe_unused]] logger_t logger = logger_t{}) {
constexpr bool doLogging = not std::is_same_v<logger_t, std::false_type>;

const Logger& logger = getDummyLogger()) {
const double cLimit = intersection.pathLength;

if constexpr (doLogging) {
ACTS_VERBOSE(" -> pLimit, oLimit, cLimit: " << pLimit << ", " << oLimit
<< ", " << cLimit);
}
ACTS_VERBOSE(" -> pLimit, oLimit, cLimit: " << pLimit << ", " << oLimit
<< ", " << cLimit);

const bool coCriterion = cLimit > oLimit;
const bool cpCriterion = std::abs(cLimit) < std::abs(pLimit) + tolerance;

const bool accept = coCriterion and cpCriterion;

if constexpr (doLogging) {
if (accept) {
ACTS_VERBOSE("Intersection is WITHIN limit");
} else {
ACTS_VERBOSE("Intersection is OUTSIDE limit because: ");
if (not coCriterion) {
ACTS_VERBOSE("- intersection path length "
<< cLimit << " <= overstep limit " << oLimit);
}
if (not cpCriterion) {
ACTS_VERBOSE("- intersection path length "
<< std::abs(cLimit) << " is over the path limit "
<< (std::abs(pLimit) + tolerance)
<< " (including tolerance of " << tolerance << ")");
}
if (accept) {
ACTS_VERBOSE("Intersection is WITHIN limit");
} else {
ACTS_VERBOSE("Intersection is OUTSIDE limit because: ");
if (not coCriterion) {
ACTS_VERBOSE("- intersection path length "
<< cLimit << " <= overstep limit " << oLimit);
}
if (not cpCriterion) {
ACTS_VERBOSE("- intersection path length "
<< std::abs(cLimit) << " is over the path limit "
<< (std::abs(pLimit) + tolerance)
<< " (including tolerance of " << tolerance << ")");
}
}

Expand Down

0 comments on commit 38926ae

Please sign in to comment.