Skip to content

Commit

Permalink
Merge pull request #16 from MuonColliderSoft/porting_v32
Browse files Browse the repository at this point in the history
Porting v32
  • Loading branch information
pandreetto authored Jul 5, 2024
2 parents 3fa0b24 + 9a14ba8 commit b820d3e
Show file tree
Hide file tree
Showing 13 changed files with 537 additions and 159 deletions.
10 changes: 10 additions & 0 deletions ACTSTracking/ACTSSeededCKFTrackingProc.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -64,13 +64,23 @@ class ACTSSeededCKFTrackingProc : public ACTSProcBase {
float _seedFinding_rMax = 150;
float _seedFinding_deltaRMin = 5;
float _seedFinding_deltaRMax = 80;
float _seedFinding_deltaRMinTop = 0;
float _seedFinding_deltaRMaxTop = 0;
float _seedFinding_deltaRMinBottom = 0;
float _seedFinding_deltaRMaxBottom = 0;
float _seedFinding_collisionRegion = 75;
float _seedFinding_zMax = 600;
float _seedFinding_sigmaScattering = 50;
float _seedFinding_radLengthPerSeed = 0.1;
float _seedFinding_minPt = 500;
float _seedFinding_impactMax = 3 * Acts::UnitConstants::mm;

StringVec _seedFinding_zBinEdges;
int _zTopBinLen = 1;
int _zBottomBinLen = 1;
int _phiTopBinLen = 1;
int _phiBottomBinLen = 1;

// Track fit parameters
double _initialTrackError_pos;
double _initialTrackError_phi;
Expand Down
2 changes: 2 additions & 0 deletions ACTSTracking/ACTSTruthTrackingProc.hxx
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
#ifndef ACTSTruthTrackingProc_h
#define ACTSTruthTrackingProc_h 1

#include <EVENT/Track.h>
#include <EVENT/TrackerHit.h>

#include <UTIL/CellIDDecoder.h>

#include <Acts/Definitions/Units.hpp>
#include "Acts/EventData/ParticleHypothesis.hpp"

#include "ACTSProcBase.hxx"

Expand Down
8 changes: 8 additions & 0 deletions ACTSTracking/GeometryContainers.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,14 @@ struct GeometryIdMultisetAccessor {
return container->equal_range(geoId);
}

// get the range of elements with requested geoId
std::pair<Iterator, Iterator> range(
const Acts::Surface& surface) const {
assert(container != nullptr);
auto [begin, end] = container->equal_range(surface.geometryId());
return {Iterator{begin}, Iterator{end}};
}

// get the element using the iterator
const Value& at(const Iterator& it) const { return *it; }
};
Expand Down
21 changes: 20 additions & 1 deletion ACTSTracking/Helpers.hxx
Original file line number Diff line number Diff line change
@@ -1,18 +1,26 @@
#pragma once

#include <EVENT/LCEvent.h>
#include <EVENT/MCParticle.h>
#include <EVENT/Track.h>
#include <EVENT/TrackState.h>

#include <Acts/EventData/TrackParameters.hpp>
#include "Acts/EventData/ParticleHypothesis.hpp"
#include <Acts/MagneticField/MagneticFieldProvider.hpp>
#include <Acts/TrackFinding/CombinatorialKalmanFilter.hpp>
#include <Acts/TrackFitting/KalmanFitter.hpp>
#include <Acts/EventData/VectorTrackContainer.hpp>
#include <Acts/EventData/VectorMultiTrajectory.hpp>

#include "SourceLink.hxx"

namespace ACTSTracking {

using TrackResult = Acts::TrackContainer<Acts::VectorTrackContainer,
Acts::VectorMultiTrajectory,
std::shared_ptr>::TrackProxy;

//! Get path to a resource file
/**
* Get absolute file of a file `inpath` by looking in the following places:
Expand Down Expand Up @@ -43,13 +51,14 @@ std::string findFile(const std::string& inpath);
*
* \return Track with equivalent parameters of the ACTS track
*/
/*
EVENT::Track* ACTS2Marlin_track(
const Acts::CombinatorialKalmanFilterResult<ACTSTracking::SourceLink>&
fitOutput,
std::size_t trackTip,
std::shared_ptr<Acts::MagneticFieldProvider> magneticField,
Acts::MagneticFieldProvider::Cache& magCache);

*/
//! Convert ACTS KF result to LCIO track class
/**
* Converted propertie are:
Expand All @@ -63,10 +72,16 @@ EVENT::Track* ACTS2Marlin_track(
*
* \return Track with equivalent parameters of the ACTS track
*/
/*
EVENT::Track* ACTS2Marlin_track(
const Acts::KalmanFitterResult<ACTSTracking::SourceLink>& fitOutput,
std::shared_ptr<Acts::MagneticFieldProvider> magneticField,
Acts::MagneticFieldProvider::Cache& magCache);
*/
EVENT::Track* ACTS2Marlin_track(
const TrackResult& fitter_res,
std::shared_ptr<Acts::MagneticFieldProvider> magneticField,
Acts::MagneticFieldProvider::Cache& magCache);

//! Convert ACTS track state class to Marlin class
/**
Expand All @@ -93,4 +108,8 @@ EVENT::TrackState* ACTS2Marlin_trackState(int location,
*/
EVENT::LCCollection* getCollection(EVENT::LCEvent* evt,
const std::string& name);

Acts::ParticleHypothesis convertParticle(const EVENT::MCParticle* mcParticle);

} // namespace ACTSTracking

32 changes: 24 additions & 8 deletions ACTSTracking/MeasurementCalibrator.hxx
Original file line number Diff line number Diff line change
@@ -1,12 +1,16 @@
#pragma once

#include <Acts/EventData/Measurement.hpp>
#include "Acts/EventData/SourceLink.hpp"
#include "Acts/EventData/VectorMultiTrajectory.hpp"
#include "Acts/Geometry/GeometryContext.hpp"
#include "Acts/Utilities/CalibrationContext.hpp"

#include "SourceLink.hxx"

namespace ACTSTracking {
//! Hit stored as an measurement
using Measurement = Acts::BoundVariantMeasurement<ACTSTracking::SourceLink>;
using Measurement = Acts::BoundVariantMeasurement;

//! Collection of measurements
using MeasurementContainer = std::vector<Measurement>;
Expand All @@ -17,7 +21,7 @@ class MeasurementCalibrator {
MeasurementCalibrator() = default;
/// Construct using a user-provided container to chose measurements from.
MeasurementCalibrator(const MeasurementContainer& measurements)
: m_measurements(&measurements) {}
: m_measurements(measurements) {}

//! Find the measurement corresponding to the source link.
/**
Expand All @@ -28,16 +32,28 @@ class MeasurementCalibrator {
template <typename parameters_t>
const Measurement& operator()(const SourceLink& sourceLink,
const parameters_t& /* parameters */) const {
assert(m_measurements and
"Undefined measurement container in DigitizedCalibrator");
assert((sourceLink.index() < m_measurements->size()) and
assert((sourceLink.index() < m_measurements.size()) and
"Source link index is outside the container bounds");
return (*m_measurements)[sourceLink.index()];
return m_measurements[sourceLink.index()];
}

void calibrate(const Acts::GeometryContext& gctx,
const Acts::CalibrationContext& cctx,
const Acts::SourceLink& sourceLink,
Acts::VectorMultiTrajectory::TrackStateProxy trackState) const {
trackState.setUncalibratedSourceLink(sourceLink);
const auto& idxSourceLink = sourceLink.get<ACTSTracking::SourceLink>();

assert((idxSourceLink.index() < m_measurements.size()) and
"Source link index is outside the container bounds");

const auto& meas = std::get<1>(m_measurements[idxSourceLink.index()]); //TODO workaround
trackState.allocateCalibrated(meas.size());
trackState.setCalibrated(meas);
}

private:
// use pointer so the calibrator is copyable and default constructible.
const MeasurementContainer* m_measurements = nullptr;
const MeasurementContainer& m_measurements;
};

} // namespace ACTSTracking
6 changes: 6 additions & 0 deletions ACTSTracking/SeedSpacePoint.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,12 @@ class SeedSpacePoint {

constexpr SourceLink sourceLink() const { return m_sourceLink; }

const std::optional<float> t() const
{
return m_sourceLink.lciohit()->getTime();
}
// TODO missing: const std::optional<float> varianceT() const

private:
// Global position
float m_x;
Expand Down
22 changes: 20 additions & 2 deletions ACTSTracking/SourceLink.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

#include <EVENT/TrackerHit.h>

#include "Acts/Surfaces/Surface.hpp"

#include "GeometryContainers.hxx"

namespace ACTSTracking {
Expand Down Expand Up @@ -46,6 +48,22 @@ class SourceLink final {

/// Container of index source links
using SourceLinkContainer = GeometryIdMultiset<SourceLink>;
// Wrapper for SourceLinkContainer for use with CKF
using SourceLinkAccessor = GeometryIdMultisetAccessor<SourceLink>;
/// Accessor for the above source link container
///
/// It wraps up a few lookup methods to be used in the Combinatorial Kalman
/// Filter
struct SourceLinkAccessor : GeometryIdMultisetAccessor<SourceLink> {
using BaseIterator = GeometryIdMultisetAccessor<SourceLink>::Iterator;

using Iterator = Acts::SourceLinkAdapterIterator<BaseIterator>;

// get the range of elements with requested geoId
std::pair<Iterator, Iterator> range(const Acts::Surface& surface) const {
assert(container != nullptr);
auto [begin, end] = container->equal_range(surface.geometryId());
return {Iterator{begin}, Iterator{end}};
}
};

} // namespace ACTSTracking

1 change: 0 additions & 1 deletion src/ACTSProcBase.cxx
Original file line number Diff line number Diff line change
Expand Up @@ -596,7 +596,6 @@ void ACTSProcBase::buildDetector() {
ringLayoutConfiguration(lbc.layerConfigurations[0]);
ringLayoutConfiguration(lbc.layerConfigurations[2]);
volumeConfig.layerBuilder = layerBuilder;
volumeConfig.volumeSignature = 0;
auto volumeBuilder = std::make_shared<const Acts::CylinderVolumeBuilder>(
volumeConfig,
Acts::getDefaultLogger(lbc.configurationName + "VolumeBuilder",
Expand Down
Loading

0 comments on commit b820d3e

Please sign in to comment.