Skip to content

Commit

Permalink
feat: Conversion and chain code in traccc
Browse files Browse the repository at this point in the history
This PR adds conversion code as well as the code to run simple host-side
chain algorithms using traccc.

Co-authored-by: Stephen Nicholas Swatman <[email protected]>
  • Loading branch information
fredevb and stephenswat committed Sep 29, 2024
1 parent 6e08612 commit ba45053
Show file tree
Hide file tree
Showing 46 changed files with 2,789 additions and 12 deletions.
5 changes: 5 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ option(ACTS_BUILD_PLUGIN_EDM4HEP "Build EDM4hep plugin" OFF)
option(ACTS_BUILD_PLUGIN_FPEMON "Build FPE monitoring plugin" OFF)
option(ACTS_BUILD_PLUGIN_GEOMODEL "Build GeoModel plugin" OFF)
option(ACTS_BUILD_PLUGIN_TRACCC "Build Traccc plugin" OFF)
option(ACTS_TRACCC_ENABLE_CUDA "Enable CUDA for the traccc plugin" OFF)
option(ACTS_BUILD_PLUGIN_GEANT4 "Build Geant4 plugin" OFF)
option(ACTS_BUILD_PLUGIN_EXATRKX "Build the Exa.TrkX plugin" OFF)
option(ACTS_EXATRKX_ENABLE_ONNX "Build the Onnx backend for the exatrkx plugin" OFF)
Expand Down Expand Up @@ -443,6 +444,10 @@ if(ACTS_BUILD_PLUGIN_GEANT4)
endif()

if(ACTS_BUILD_PLUGIN_TRACCC)
# TODO: Algebra-plugins should set this up itself!
# Can be removed with traccc 0.16.0.
add_definitions(-DALGEBRA_PLUGINS_INCLUDE_ARRAY)

if(ACTS_USE_SYSTEM_ALGEBRAPLUGINS)
find_package(algebra-plugins ${_acts_algebraplugins_version} REQUIRED)
else()
Expand Down
6 changes: 6 additions & 0 deletions Examples/Algorithms/Traccc/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,10 @@ target_link_libraries(
ActsPluginDetray
)

add_subdirectory(Common)
target_link_libraries(ActsExamplesTraccc INTERFACE ActsExamplesTracccCommon)

add_subdirectory(Host)
target_link_libraries(ActsExamplesTraccc INTERFACE ActsExamplesTracccHost)

install(TARGETS ActsExamplesTraccc LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR})
23 changes: 23 additions & 0 deletions Examples/Algorithms/Traccc/Common/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
add_library(
ActsExamplesTracccCommon
SHARED
src/Conversion/CellMapConversion.cpp
src/Conversion/DigitizationConversion.cpp
src/Conversion/MeasurementConversion.cpp
src/Debug/Debug.cpp
)

target_include_directories(
ActsExamplesTracccCommon
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
)

target_link_libraries(
ActsExamplesTracccCommon
PUBLIC ActsPluginTraccc ActsExamplesFramework ActsExamplesDigitization
)

install(
TARGETS ActsExamplesTracccCommon
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
// This file is part of the Acts project.
//
// Copyright (C) 2024 CERN for the benefit of the Acts project
//
// This Source Code Form is subject to the terms of the Mozilla Public
// License, v. 2.0. If a copy of the MPL was not distributed with this
// file, You can obtain one at http://mozilla.org/MPL/2.0/.

#pragma once

#include "Acts/Geometry/GeometryIdentifier.hpp"
#include "ActsExamples/EventData/Cluster.hpp"

#include <cstdint>
#include <cstdlib>
#include <map>
#include <vector>

#include "traccc/edm/cell.hpp"

namespace ActsExamples::Traccc::Common::Conversion {

/// @brief Converts a "geometry ID -> generic cell collection type" map to a "geometry ID -> traccc cell collection" map.
/// @note The function sets the module link of the cells in the output to 0.
/// @return Map from geometry ID to its cell data (as a vector of traccc cell data)
std::map<std::uint64_t, std::vector<traccc::cell>> tracccCellsMap(
const std::map<Acts::GeometryIdentifier, std::vector<Cluster::Cell>>& map);

} // namespace ActsExamples::Traccc::Common::Conversion
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
// This file is part of the Acts project.
//
// Copyright (C) 2023 CERN for the benefit of the Acts project
//
// This Source Code Form is subject to the terms of the Mozilla Public
// License, v. 2.0. If a copy of the MPL was not distributed with this
// file, You can obtain one at http://mozilla.org/MPL/2.0/.

#pragma once

// Acts include(s)
#include "Acts/Geometry/GeometryHierarchyMap.hpp"

// Acts plugin include(s)
#include "Acts/Plugins/Traccc/DigitizationConfig.hpp"

// Acts Examples include(s)
#include "ActsExamples/Digitization/DigitizationConfig.hpp"

namespace ActsExamples::Traccc::Common::Conversion {

/// @brief Creates a traccc digitalization config from an Acts geometry hierarchy map
/// that contains the digitization configuration.
/// @param config the Acts geometry hierarchy map that contains the digitization configuration.
/// @return a traccc digitization config.
Acts::TracccPlugin::DigitizationConfig tracccConfig(
const Acts::GeometryHierarchyMap<DigiComponentsConfig>& config);

} // namespace ActsExamples::Traccc::Common::Conversion
Original file line number Diff line number Diff line change
@@ -0,0 +1,206 @@
// This file is part of the Acts project.
//
// Copyright (C) 2023 CERN for the benefit of the Acts project
//
// This Source Code Form is subject to the terms of the Mozilla Public
// License, v. 2.0. If a copy of the MPL was not distributed with this
// file, You can obtain one at http://mozilla.org/MPL/2.0/.

#pragma once

// Plugin include(s)
#include "Acts/Plugins/Traccc/Detail/AlgebraConversion.hpp"

// Acts include(s)
#include "Acts/Definitions/Algebra.hpp"
#include "Acts/Definitions/TrackParametrization.hpp"
#include "Acts/EventData/SourceLink.hpp"
#include "Acts/Geometry/GeometryIdentifier.hpp"
#include "ActsExamples/EventData/Measurement.hpp"

// Acts Examples include(s)
#include "ActsExamples/EventData/IndexSourceLink.hpp"
#include "ActsExamples/Traccc/Util/MapUtil.hpp"

// Detray include(s)
#include "detray/core/detector.hpp"
#include "detray/tracks/bound_track_parameters.hpp"

// Traccc include(s)
#include "traccc/definitions/qualifiers.hpp"
#include "traccc/definitions/track_parametrization.hpp"
#include "traccc/edm/measurement.hpp"
#include "traccc/edm/track_state.hpp"

// System include(s)
#include <cstdint>
#include <cstdlib>
#include <memory>
#include <variant>
#include <vector>

namespace ActsExamples::Traccc::Common::Conversion {

// Custom hash and equals functions
// as some are not defined by std::hash and std::equal_to

struct TracccMeasurementHash {
std::size_t operator()(const traccc::measurement& s) const noexcept {
return s.measurement_id;
}
};

struct ActsMeasurementHash {
std::size_t operator()(
const ActsExamples::MeasurementContainer::ConstVariableProxy& s)
const noexcept {
return static_cast<std::size_t>(
s.sourceLink().get<ActsExamples::IndexSourceLink>().index());
}
};

struct ActsMeasurementEquals {
bool operator()(
const ActsExamples::MeasurementContainer::ConstVariableProxy& m1,
const ActsExamples::MeasurementContainer::ConstVariableProxy& m2) const {
auto lhsIdx = m1.sourceLink().get<ActsExamples::IndexSourceLink>().index();
auto rhsIdx = m2.sourceLink().get<ActsExamples::IndexSourceLink>().index();
return lhsIdx == rhsIdx;
}
};

/// @brief Converts a traccc bound index to an Acts bound index.
/// @param tracccBoundIndex the traccc bound index.
/// @returns an Acts bound index.
Acts::BoundIndices boundIndex(const traccc::bound_indices tracccBoundIndex);

/// @brief Gets the the local position of the measurement.
/// @param measurement the Acts measurement.
/// @returns A two-dimensional vector containing the local position.
/// The first item in the vector is local position on axis 0 and
/// I.e., [local position (axis 0), local position (axis 1)].
/// @note if the dimension is less than 2 then the remaining values are set to 0.
template <std::size_t dim>
inline Acts::ActsVector<2> getLocal(
const ActsExamples::MeasurementContainer::ConstFixedProxy<dim>&
measurement) {
traccc::scalar loc0 = 0;
traccc::scalar loc1 = 0;
if constexpr (dim > Acts::BoundIndices::eBoundLoc0) {
loc0 = measurement.parameters()(Acts::BoundIndices::eBoundLoc0);
}
if constexpr (dim > Acts::BoundIndices::eBoundLoc1) {
loc1 = measurement.parameters()(Acts::BoundIndices::eBoundLoc1);
}
return Acts::ActsVector<2>(loc0, loc1);
}

/// @brief Get the the local position of the measurement.
/// @param measurement the Acts bound variant measurement.
/// @return A two-dimensional vector containing the local position.
/// I.e., [local position (axis 0), local position (axis 1)].
/// @note if the dimension is less than 2 then the remaining values are set to 0.
inline Acts::ActsVector<2> getLocal(
const ActsExamples::MeasurementContainer::ConstVariableProxy& measurement) {
traccc::scalar loc0 = 0;
traccc::scalar loc1 = 0;
if (measurement.size() > Acts::BoundIndices::eBoundLoc0) {
loc0 = measurement.parameters()(Acts::BoundIndices::eBoundLoc0);
}
if (measurement.size() > Acts::BoundIndices::eBoundLoc1) {
loc1 = measurement.parameters()(Acts::BoundIndices::eBoundLoc1);
}
return Acts::ActsVector<2>(loc0, loc1);
}

/// @brief Get the the variance of the measurement.
/// @param measurement the Acts measurement.
/// @return A two-dimensional vector containing the variance.
/// I.e., [variance (axis 0), variance (axis 1)].
/// @note if the dimension is less than 2 then the remaining values are set to 0.
template <std::size_t dim>
inline Acts::ActsVector<2> getVariance(
const ActsExamples::MeasurementContainer::ConstFixedProxy<dim>&
measurement) {
traccc::scalar var0 = 0;
traccc::scalar var1 = 0;
if constexpr (dim >= Acts::BoundIndices::eBoundLoc0) {
var0 = measurement.covariance()(Acts::BoundIndices::eBoundLoc0,
Acts::BoundIndices::eBoundLoc0);
}
if constexpr (dim > Acts::BoundIndices::eBoundLoc1) {
var1 = measurement.covariance()(Acts::BoundIndices::eBoundLoc1,
Acts::BoundIndices::eBoundLoc1);
}
return Acts::ActsVector<2>(var0, var1);
}

/// @brief Get the the variance of the measurement.
/// @param measurement the Acts bound variant measurement.
/// @return A two-dimensional vector containing the variance.
/// I.e., [variance (axis 0), variance (axis 1)].
/// @note if the dimension is less than 2 then the remaining values are set to 0.
inline Acts::ActsVector<2> getVariance(
const ActsExamples::MeasurementContainer::ConstVariableProxy& measurement) {
traccc::scalar var0 = 0;
traccc::scalar var1 = 0;
if (measurement.size() >= Acts::BoundIndices::eBoundLoc0) {
var0 = measurement.covariance()(Acts::BoundIndices::eBoundLoc0,
Acts::BoundIndices::eBoundLoc0);
}
if (measurement.size() > Acts::BoundIndices::eBoundLoc1) {
var1 = measurement.covariance()(Acts::BoundIndices::eBoundLoc1,
Acts::BoundIndices::eBoundLoc1);
}
return Acts::ActsVector<2>(var0, var1);
}

/// @brief Get the geometry ID from the measurement through its source link.
/// @note The sourcelink is assumed to be of type IndexSourceLink.
inline Acts::GeometryIdentifier getGeometryID(
const ActsExamples::MeasurementContainer::ConstVariableProxy& measurement) {
return measurement.sourceLink()
.template get<ActsExamples::IndexSourceLink>()
.geometryId();
}

/// @brief Converts traccc measurements to acts measurements.
/// @param detector The detray detector,
/// @param measurements The traccc measurements,
/// @return A vector of Acts bound variant measurements.
/// @note The type IndexSourceLink is used for the measurements' source links.
template <typename detector_t, typename iterator_t>
inline auto convertMeasurements(const detector_t& detector,
iterator_t measurements_begin,
iterator_t measurements_end,
MeasurementContainer& measurementContainer) {
for (iterator_t i = measurements_begin; i != measurements_end; ++i) {
Acts::GeometryIdentifier moduleGeoId(
detector.surface((*i).surface_link).source);
Index measurementIdx = measurementContainer.size();
IndexSourceLink idxSourceLink{moduleGeoId, measurementIdx};

Eigen::Matrix<MeasurementContainer::VariableProxy::SubspaceIndex,
Eigen::Dynamic, 1>
indices(2);

for (unsigned int j = 0; j < 2; j++) {
indices[j] =
boundIndex(traccc::bound_indices((*i).subs.get_indices()[j]));
}

measurementContainer.emplaceMeasurement<2>(
Acts::SourceLink{idxSourceLink}, indices,
Acts::TracccPlugin::detail::toActsVector<2>((*i).local),
Eigen::DiagonalMatrix<Acts::ActsScalar, static_cast<int>(2)>(
Acts::TracccPlugin::detail::toActsVector<2>((*i).variance))
.toDenseMatrix());
}

return Util::makeConversionOneToOne(
measurements_begin, measurements_end, measurementContainer.cbegin(),
measurementContainer.cend(), TracccMeasurementHash{},
std::equal_to<traccc::measurement>{});
}

} // namespace ActsExamples::Traccc::Common::Conversion
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
// This file is part of the Acts project.
//
// Copyright (C) 2023 CERN for the benefit of the Acts project
//
// This Source Code Form is subject to the terms of the Mozilla Public
// License, v. 2.0. If a copy of the MPL was not distributed with this
// file, You can obtain one at http://mozilla.org/MPL/2.0/.

#pragma once

// Acts include(s)
#include "ActsExamples/EventData/Measurement.hpp"

// Acts Examples include(s)
#include "ActsExamples/Traccc/Conversion/MeasurementConversion.hpp"
#include "ActsExamples/Traccc/Util/IndexMap.hpp"
#include "ActsExamples/Traccc/Util/MapUtil.hpp"

// Traccc include(s)
#include "traccc/edm/measurement.hpp"

// System include(s)
#include <cstdint>
#include <cstdlib>
#include <memory>
#include <variant>
#include <vector>

namespace ActsExamples::Traccc::Common::Conversion {

/// @brief Checks if two measurements are equal based on their geometry ID and position alone.
/// @note max_dist is the tolerance of distance in local position.
/// The distance between the local positions of the measurements must be
/// less or equal to this value to be considered equal.
/// @returns true or false depending on whether they are considered equal.
struct MeasurementAproxEquals {
bool operator()(const ActsExamples::MeasurementContainer::ConstVariableProxy&
measurement1,
const ActsExamples::MeasurementContainer::ConstVariableProxy&
measurement2) const {
auto gidEq = Conversion::getGeometryID(measurement1) ==
Conversion::getGeometryID(measurement2);

auto sqNorm = (Conversion::getLocal(measurement1) -
Conversion::getLocal(measurement2))
.squaredNorm();
auto locEq = sqNorm <= .001 * .001;

return gidEq && locEq;
}
};

/// @brief Generates a hash for the measurement.
/// This hash is used for the locality sensitive hashing to calculate the match
/// map. Thus, this hash is not sensitive to small variations in position that
/// could could from numerical errors.
struct MeasurementGeoIDHash {
bool operator()(const ActsExamples::MeasurementContainer::ConstVariableProxy&
measurement) const {
return static_cast<std::size_t>(
Conversion::getGeometryID(measurement).value());
}
};
} // namespace ActsExamples::Traccc::Common::Conversion
Loading

0 comments on commit ba45053

Please sign in to comment.