Skip to content

Commit

Permalink
Merge branch 'main' into contains
Browse files Browse the repository at this point in the history
  • Loading branch information
AJPfleger authored Sep 6, 2024
2 parents 14397d1 + 26b059f commit c24c589
Show file tree
Hide file tree
Showing 43 changed files with 221 additions and 180 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -262,7 +262,7 @@ class MultiComponentCurvilinearTrackParameters
avgDir += w * dir;
}

auto s = Surface::makeShared<PlaneSurface>(avgPos, avgDir);
auto s = CurvilinearSurface(avgPos, avgDir).planeSurface();

std::vector<std::tuple<double, BoundVector, covariance_t>> bound;
bound.reserve(curvi.size());
Expand Down
9 changes: 0 additions & 9 deletions Core/include/Acts/Surfaces/PlaneSurface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,15 +58,6 @@ class PlaneSurface : public RegularSurface {
PlaneSurface(const GeometryContext& gctx, const PlaneSurface& other,
const Transform3& transform);

/// @deprecated Use `CurvilinearSurface` instead
///
/// Dedicated Constructor with normal vector
/// This is for curvilinear surfaces which are by definition boundless
///
/// @param center is the center position of the surface
/// @param normal is thenormal vector of the plane surface
PlaneSurface(const Vector3& center, const Vector3& normal);

/// Constructor from DetectorElementBase : Element proxy
///
/// @param pbounds are the provided planar bounds
Expand Down
36 changes: 33 additions & 3 deletions Core/include/Acts/TrackFinding/CombinatorialKalmanFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -1235,7 +1235,9 @@ class CombinatorialKalmanFilter {
/// @param initialParameters The initial track parameters
/// @param tfOptions CombinatorialKalmanFilterOptions steering the track
/// finding
/// @param trackContainer Input track container to use
/// @param trackContainer Track container in which to store the results
/// @param rootBranch The track to be used as the root branch
///
/// @note The input measurements are given in the form of @c SourceLinks.
/// It's @c calibrator_t's job to turn them into calibrated measurements
/// used in the track finding.
Expand All @@ -1247,7 +1249,8 @@ class CombinatorialKalmanFilter {
auto findTracks(const start_parameters_t& initialParameters,
const CombinatorialKalmanFilterOptions<
source_link_iterator_t, track_container_t>& tfOptions,
track_container_t& trackContainer) const
track_container_t& trackContainer,
typename track_container_t::TrackProxy rootBranch) const
-> Result<std::vector<
typename std::decay_t<decltype(trackContainer)>::TrackProxy>> {
using SourceLinkAccessor =
Expand Down Expand Up @@ -1310,7 +1313,6 @@ class CombinatorialKalmanFilter {
r.tracks = &trackContainer;
r.trackStates = &trackContainer.trackStateContainer();

auto rootBranch = trackContainer.makeTrack();
r.activeBranches.push_back(rootBranch);

auto propagationResult = m_propagator.propagate(propState);
Expand Down Expand Up @@ -1349,6 +1351,34 @@ class CombinatorialKalmanFilter {

return std::move(combKalmanResult.collectedTracks);
}

/// Combinatorial Kalman Filter implementation, calls the Kalman filter
///
/// @tparam source_link_iterator_t Type of the source link iterator
/// @tparam start_parameters_t Type of the initial parameters
/// @tparam parameters_t Type of parameters used for local parameters
///
/// @param initialParameters The initial track parameters
/// @param tfOptions CombinatorialKalmanFilterOptions steering the track
/// finding
/// @param trackContainer Track container in which to store the results
/// @note The input measurements are given in the form of @c SourceLinks.
/// It's @c calibrator_t's job to turn them into calibrated measurements
/// used in the track finding.
///
/// @return a container of track finding result for all the initial track
/// parameters
template <typename source_link_iterator_t, typename start_parameters_t,
typename parameters_t = BoundTrackParameters>
auto findTracks(const start_parameters_t& initialParameters,
const CombinatorialKalmanFilterOptions<
source_link_iterator_t, track_container_t>& tfOptions,
track_container_t& trackContainer) const
-> Result<std::vector<
typename std::decay_t<decltype(trackContainer)>::TrackProxy>> {
auto rootBranch = trackContainer.makeTrack();
return findTracks(initialParameters, tfOptions, trackContainer, rootBranch);
}
};

} // namespace Acts
14 changes: 0 additions & 14 deletions Core/include/Acts/Utilities/Intersection.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,13 +59,6 @@ class Intersection {
Status status)
: m_position(position), m_pathLength(pathLength), m_status(status) {}

/// Returns whether the intersection was successful or not
/// @deprecated
[[deprecated("Use isValid() instead")]] constexpr explicit operator bool()
const {
return isValid();
}

/// Returns whether the intersection was successful or not
constexpr bool isValid() const { return m_status != Status::missed; }

Expand Down Expand Up @@ -149,13 +142,6 @@ class ObjectIntersection {
const object_t* object, std::uint8_t index = 0)
: m_intersection(intersection), m_object(object), m_index(index) {}

/// Returns whether the intersection was successful or not
/// @deprecated
[[deprecated("Use isValid() instead")]] constexpr explicit operator bool()
const {
return isValid();
}

/// Returns whether the intersection was successful or not
constexpr bool isValid() const { return m_intersection.isValid(); }

Expand Down
9 changes: 0 additions & 9 deletions Core/include/Acts/Vertexing/Vertex.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,15 +78,6 @@ class Vertex {
/// @param position Vertex position
void setPosition(const Vector3& position);

/// @brief Set position and time
///
/// @deprecated Use setFullPosition instead
///
/// @param position Vertex position
/// @param time The time
[[deprecated("Use setFullPosition instead")]] void setPosition(
const Vector3& position, ActsScalar time);

/// @brief Set position and time
///
/// @param fullPosition Vertex position and time
Expand Down
6 changes: 0 additions & 6 deletions Core/src/Surfaces/PlaneSurface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,12 +37,6 @@ Acts::PlaneSurface::PlaneSurface(const GeometryContext& gctx,
RegularSurface(gctx, other, transform),
m_bounds(other.m_bounds) {}

Acts::PlaneSurface::PlaneSurface(const Vector3& center, const Vector3& normal)
: RegularSurface(), m_bounds(nullptr) {
m_transform = std::make_unique<Transform3>(
CurvilinearSurface(center, normal).transform());
}

Acts::PlaneSurface::PlaneSurface(std::shared_ptr<const PlanarBounds> pbounds,
const Acts::DetectorElementBase& detelement)
: RegularSurface(detelement), m_bounds(std::move(pbounds)) {
Expand Down
5 changes: 0 additions & 5 deletions Core/src/Vertexing/Vertex.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,11 +81,6 @@ void Vertex::setPosition(const Vector3& position) {
m_position.head<3>() = position;
}

void Vertex::setPosition(const Vector3& position, ActsScalar time) {
m_position.head<3>() = position;
m_position[eTime] = time;
}

void Vertex::setFullPosition(const Vector4& fullPosition) {
m_position = fullPosition;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ class TrackFindingAlgorithm final : public IAlgorithm {
virtual ~TrackFinderFunction() = default;
virtual TrackFinderResult operator()(const TrackParameters&,
const TrackFinderOptions&,
TrackContainer&) const = 0;
TrackContainer&, TrackProxy) const = 0;
};

/// Create the track finder function implementation.
Expand Down
12 changes: 8 additions & 4 deletions Examples/Algorithms/TrackFinding/src/TrackFindingAlgorithm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -470,8 +470,9 @@ ProcessCode TrackFindingAlgorithm::execute(const AlgorithmContext& ctx) const {
const Acts::BoundTrackParameters& firstInitialParameters =
initialParameters.at(iSeed);

auto firstResult =
(*m_cfg.findTracks)(firstInitialParameters, firstOptions, tracksTemp);
auto firstRootBranch = tracksTemp.makeTrack();
auto firstResult = (*m_cfg.findTracks)(firstInitialParameters, firstOptions,
tracksTemp, firstRootBranch);
nSeed++;

if (!firstResult.ok()) {
Expand Down Expand Up @@ -531,8 +532,11 @@ ProcessCode TrackFindingAlgorithm::execute(const AlgorithmContext& ctx) const {
Acts::BoundTrackParameters secondInitialParameters =
trackCandidate.createParametersFromState(*firstMeasurement);

auto secondResult = (*m_cfg.findTracks)(secondInitialParameters,
secondOptions, tracksTemp);
auto secondRootBranch = tracksTemp.makeTrack();
secondRootBranch.copyFrom(trackCandidate, false);
auto secondResult =
(*m_cfg.findTracks)(secondInitialParameters, secondOptions,
tracksTemp, secondRootBranch);

if (!secondResult.ok()) {
ACTS_WARNING("Second track finding failed for seed "
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,10 @@ struct TrackFinderFunctionImpl
ActsExamples::TrackFindingAlgorithm::TrackFinderResult operator()(
const ActsExamples::TrackParameters& initialParameters,
const ActsExamples::TrackFindingAlgorithm::TrackFinderOptions& options,
ActsExamples::TrackContainer& tracks) const override {
return trackFinder.findTracks(initialParameters, options, tracks);
ActsExamples::TrackContainer& tracks,
ActsExamples::TrackProxy rootBranch) const override {
return trackFinder.findTracks(initialParameters, options, tracks,
rootBranch);
};
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,9 @@ ActsExamples::ProcessCode TrackFindingFromPrototrackAlgorithm::execute(
}
}

auto result = (*m_cfg.findTracks)(initialParameters.at(i), options, tracks);
auto rootBranch = tracks.makeTrack();
auto result = (*m_cfg.findTracks)(initialParameters.at(i), options, tracks,
rootBranch);
nSeed++;

if (!result.ok()) {
Expand Down
6 changes: 3 additions & 3 deletions Tests/UnitTests/Core/EventData/BoundTrackParametersTests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -252,9 +252,9 @@ const auto perigees = bdata::make({
Surface::makeShared<PerigeeSurface>(Vector3(0, 0, -1.5)),
});
const auto planes = bdata::make({
Surface::makeShared<PlaneSurface>(Vector3(1, 2, 3), Vector3::UnitX()),
Surface::makeShared<PlaneSurface>(Vector3(-2, -3, -4), Vector3::UnitY()),
Surface::makeShared<PlaneSurface>(Vector3(3, -4, 5), Vector3::UnitZ()),
CurvilinearSurface(Vector3(1, 2, 3), Vector3::UnitX()).planeSurface(),
CurvilinearSurface(Vector3(-2, -3, -4), Vector3::UnitY()).planeSurface(),
CurvilinearSurface(Vector3(3, -4, 5), Vector3::UnitZ()).planeSurface(),
});
const auto straws = bdata::make({
Surface::makeShared<StrawSurface>(Transform3::Identity(), 2.0 /* radius */,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include "Acts/EventData/detail/CorrectedTransformationFreeToBound.hpp"
#include "Acts/Geometry/GeometryContext.hpp"
#include "Acts/Surfaces/BoundaryTolerance.hpp"
#include "Acts/Surfaces/CurvilinearSurface.hpp"
#include "Acts/Surfaces/PlaneSurface.hpp"
#include "Acts/Surfaces/Surface.hpp"
#include "Acts/Tests/CommonHelpers/FloatComparisons.hpp"
Expand Down Expand Up @@ -54,8 +55,8 @@ BOOST_AUTO_TEST_CASE(CorrectedFreeToBoundTrackParameters) {

// construct two parallel plane surfaces with normal in x direction
ActsScalar distance = 10_mm;
auto eSurface = Surface::makeShared<PlaneSurface>(Vector3(distance, 0, 0),
Vector3::UnitX());
auto eSurface = CurvilinearSurface(Vector3(distance, 0, 0), Vector3::UnitX())
.planeSurface();

// the bound parameters at the starting plane
BoundVector sBoundParams = BoundVector::Zero();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include "Acts/EventData/GenericBoundTrackParameters.hpp"
#include "Acts/EventData/ParticleHypothesis.hpp"
#include "Acts/Geometry/GeometryContext.hpp"
#include "Acts/Surfaces/CurvilinearSurface.hpp"
#include "Acts/Surfaces/Surface.hpp"
#include <Acts/EventData/Charge.hpp>
#include <Acts/EventData/MultiComponentTrackParameters.hpp>
Expand All @@ -38,8 +39,9 @@ BOOST_AUTO_TEST_CASE(test_constructors) {
b;
b.push_back({1.0, BoundVector::Ones(), BoundSquareMatrix::Identity()});

auto surface = Acts::Surface::makeShared<Acts::PlaneSurface>(
Vector3::Ones(), Vector3::Ones().normalized());
auto surface =
CurvilinearSurface(Vector3::Ones(), Vector3::Ones().normalized())
.planeSurface();

const auto ap =
MultiComponentBoundTrackParameters(surface, a, particleHypothesis);
Expand All @@ -62,8 +64,9 @@ BOOST_AUTO_TEST_CASE(test_accessors) {
using cov_t = std::optional<BoundSquareMatrix>;
for (const auto &cov : {cov_t{}, cov_t{BoundSquareMatrix::Identity()},
cov_t{BoundSquareMatrix::Identity()}}) {
auto surface = Acts::Surface::makeShared<Acts::PlaneSurface>(
Vector3::Ones(), Vector3::Ones().normalized());
auto surface =
CurvilinearSurface(Vector3::Ones(), Vector3::Ones().normalized())
.planeSurface();

const BoundTrackParameters single_pars(surface, BoundVector::Ones(), cov,
particleHypothesis);
Expand Down
7 changes: 4 additions & 3 deletions Tests/UnitTests/Core/EventData/TrackParametersDatasets.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include <boost/test/data/test_case.hpp>

#include "Acts/Definitions/Units.hpp"
#include "Acts/Surfaces/CurvilinearSurface.hpp"
#include "Acts/Surfaces/CylinderSurface.hpp"
#include "Acts/Surfaces/DiscSurface.hpp"
#include "Acts/Surfaces/PerigeeSurface.hpp"
Expand All @@ -34,9 +35,9 @@ const auto surfaces =
Transform3::Identity(), 10 /* radius */, 100 /* half-length z */),
// TODO perigee roundtrip local->global->local does not seem to work
// Surface::makeShared<PerigeeSurface>(Vector3(0, 0, -1.5)),
Surface::makeShared<PlaneSurface>(Vector3::Zero(), Vector3::UnitX()),
Surface::makeShared<PlaneSurface>(Vector3::Zero(), Vector3::UnitY()),
Surface::makeShared<PlaneSurface>(Vector3::Zero(), Vector3::UnitZ()),
CurvilinearSurface(Vector3::Zero(), Vector3::UnitX()).planeSurface(),
CurvilinearSurface(Vector3::Zero(), Vector3::UnitY()).planeSurface(),
CurvilinearSurface(Vector3::Zero(), Vector3::UnitZ()).planeSurface(),
});
// positions
const auto posAngle = bdata::xrange(-M_PI, M_PI, 0.50);
Expand Down
6 changes: 4 additions & 2 deletions Tests/UnitTests/Core/EventData/TrackTestsExtra.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
#include "Acts/EventData/ProxyAccessor.hpp"
#include "Acts/EventData/VectorMultiTrajectory.hpp"
#include "Acts/EventData/VectorTrackContainer.hpp"
#include "Acts/Surfaces/CurvilinearSurface.hpp"
#include "Acts/Surfaces/PlaneSurface.hpp"
#include "Acts/Utilities/Zip.hpp"

Expand Down Expand Up @@ -216,8 +217,9 @@ BOOST_AUTO_TEST_CASE_TEMPLATE(Build, factory_t, holder_types) {
t.covariance() = cov;
BOOST_CHECK_EQUAL(t.covariance(), cov);

auto surface = Acts::Surface::makeShared<Acts::PlaneSurface>(
Acts::Vector3{-3_m, 0., 0.}, Acts::Vector3{1., 0., 0});
auto surface =
CurvilinearSurface(Acts::Vector3{-3_m, 0., 0.}, Acts::Vector3{1., 0., 0})
.planeSurface();

t.setReferenceSurface(surface);
BOOST_CHECK_EQUAL(surface.get(), &t.referenceSurface());
Expand Down
9 changes: 5 additions & 4 deletions Tests/UnitTests/Core/Propagator/AtlasStepperTests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include "Acts/Propagator/AtlasStepper.hpp"
#include "Acts/Propagator/ConstrainedStep.hpp"
#include "Acts/Surfaces/BoundaryTolerance.hpp"
#include "Acts/Surfaces/CurvilinearSurface.hpp"
#include "Acts/Surfaces/DiscSurface.hpp"
#include "Acts/Surfaces/PerigeeSurface.hpp"
#include "Acts/Surfaces/PlaneSurface.hpp"
Expand Down Expand Up @@ -183,7 +184,7 @@ BOOST_AUTO_TEST_CASE(UpdateFromBound) {
auto newAbsMom = 0.9 * absMom;

// example surface and bound parameters at the updated position
auto plane = Surface::makeShared<PlaneSurface>(newPos, newUnitDir);
auto plane = CurvilinearSurface(newPos, newUnitDir).planeSurface();
auto params =
BoundTrackParameters::create(plane, geoCtx, newPos4, newUnitDir,
charge / absMom, cov, particleHypothesis)
Expand Down Expand Up @@ -242,7 +243,7 @@ BOOST_AUTO_TEST_CASE(BuildBound) {
particleHypothesis),
stepSize, tolerance);
// example surface at the current state position
auto plane = Surface::makeShared<PlaneSurface>(pos, unitDir);
auto plane = CurvilinearSurface(pos, unitDir).planeSurface();

auto&& [pars, jac, pathLength] = stepper.boundState(state, *plane).value();
// check parameters
Expand Down Expand Up @@ -578,8 +579,8 @@ BOOST_AUTO_TEST_CASE(StepSizeSurface) {
stepSize, tolerance);

auto distance = 10_mm;
auto target = Surface::makeShared<PlaneSurface>(
pos + navDir * distance * unitDir, unitDir);
auto target = CurvilinearSurface(pos + navDir * distance * unitDir, unitDir)
.planeSurface();

stepper.updateSurfaceStatus(state, *target, 0, navDir,
BoundaryTolerance::Infinite());
Expand Down
2 changes: 1 addition & 1 deletion Tests/UnitTests/Core/Propagator/CovarianceEngineTests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ BOOST_AUTO_TEST_CASE(covariance_engine_test) {

// Repeat transport to surface
FreeToBoundCorrection freeToBoundCorrection(false);
auto surface = Surface::makeShared<PlaneSurface>(position, direction);
auto surface = CurvilinearSurface(position, direction).planeSurface();
detail::transportCovarianceToBound(
tgContext, *surface, covariance, jacobian, transportJacobian, derivatives,
boundToFreeJacobian, parameters, freeToBoundCorrection);
Expand Down
5 changes: 3 additions & 2 deletions Tests/UnitTests/Core/Propagator/EigenStepperTests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include "Acts/Propagator/StepperExtensionList.hpp"
#include "Acts/Propagator/detail/Auctioneer.hpp"
#include "Acts/Surfaces/BoundaryTolerance.hpp"
#include "Acts/Surfaces/CurvilinearSurface.hpp"
#include "Acts/Surfaces/PlaneSurface.hpp"
#include "Acts/Surfaces/RectangleBounds.hpp"
#include "Acts/Surfaces/Surface.hpp"
Expand Down Expand Up @@ -448,7 +449,7 @@ BOOST_AUTO_TEST_CASE(eigen_stepper_test) {
BOOST_CHECK_EQUAL(esStateCopy.previousStepSize, ps.stepping.previousStepSize);

/// Repeat with surface related methods
auto plane = Surface::makeShared<PlaneSurface>(pos, dir.normalized());
auto plane = CurvilinearSurface(pos, dir.normalized()).planeSurface();
auto bp = BoundTrackParameters::create(
plane, tgContext, makeVector4(pos, time), dir, charge / absMom,
cov, ParticleHypothesis::pion())
Expand All @@ -458,7 +459,7 @@ BOOST_AUTO_TEST_CASE(eigen_stepper_test) {

// Test the intersection in the context of a surface
auto targetSurface =
Surface::makeShared<PlaneSurface>(pos + navDir * 2. * dir, dir);
CurvilinearSurface(pos + navDir * 2. * dir, dir).planeSurface();
es.updateSurfaceStatus(esState, *targetSurface, 0, navDir,
BoundaryTolerance::Infinite());
CHECK_CLOSE_ABS(esState.stepSize.value(ConstrainedStep::actor), navDir * 2.,
Expand Down
Loading

0 comments on commit c24c589

Please sign in to comment.