Skip to content

Commit

Permalink
Merge branch 'main' into license
Browse files Browse the repository at this point in the history
  • Loading branch information
AJPfleger authored Oct 1, 2024
2 parents 86eafd8 + aa53675 commit da9b89c
Show file tree
Hide file tree
Showing 21 changed files with 61 additions and 180 deletions.
1 change: 1 addition & 0 deletions .merge-sentinel.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ rules:
required_checks:
- Docs / docs
- Analysis / build_debug
- SonarCloud Code Analysis

required_pattern:
- "Builds / *"
Expand Down
5 changes: 3 additions & 2 deletions Core/include/Acts/EventData/TrackStateType.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include <cstdint>
#include <limits>
#include <ostream>
#include <type_traits>

namespace Acts {

Expand All @@ -38,7 +39,7 @@ class TrackStateType {
public:
using raw_type = std::uint64_t;
static constexpr std::size_t kRawBits =
std::numeric_limits<std::make_unsigned<raw_type>::type>::digits;
std::numeric_limits<std::make_unsigned_t<raw_type>>::digits;

// Delete default constructor
TrackStateType() = delete;
Expand Down Expand Up @@ -106,7 +107,7 @@ class ConstTrackStateType {
public:
using raw_type = std::uint64_t;
static constexpr std::size_t kRawBits =
std::numeric_limits<std::make_unsigned<raw_type>::type>::digits;
std::numeric_limits<std::make_unsigned_t<raw_type>>::digits;

// Delete default constructor
ConstTrackStateType() = delete;
Expand Down
13 changes: 6 additions & 7 deletions Core/include/Acts/Propagator/Propagator.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
#include "Acts/Propagator/StandardAborters.hpp"
#include "Acts/Propagator/detail/LoopProtection.hpp"

#include <type_traits>
#include <concepts>

namespace Acts::detail {
template <typename Stepper, typename StateType, typename N>
Expand Down Expand Up @@ -113,9 +113,8 @@ auto Acts::Propagator<S, N>::propagate(const parameters_t& start,
-> Result<
actor_list_t_result_t<StepperCurvilinearTrackParameters,
typename propagator_options_t::actor_list_type>> {
static_assert(
std::is_copy_constructible<StepperCurvilinearTrackParameters>::value,
"return track parameter type must be copy-constructible");
static_assert(std::copy_constructible<StepperCurvilinearTrackParameters>,
"return track parameter type must be copy-constructible");

auto state = makeState(start, options);

Expand Down Expand Up @@ -158,7 +157,7 @@ auto Acts::Propagator<S, N>::makeState(
// Type of track parameters produced by the propagation
using ReturnParameterType = StepperCurvilinearTrackParameters;

static_assert(std::is_copy_constructible<ReturnParameterType>::value,
static_assert(std::copy_constructible<ReturnParameterType>,
"return track parameter type must be copy-constructible");

// Expand the abort list with a path aborter
Expand Down Expand Up @@ -246,7 +245,7 @@ auto Acts::Propagator<S, N>::makeResult(propagator_state_t state,
// Type of track parameters produced by the propagation
using ReturnParameterType = StepperCurvilinearTrackParameters;

static_assert(std::is_copy_constructible<ReturnParameterType>::value,
static_assert(std::copy_constructible<ReturnParameterType>,
"return track parameter type must be copy-constructible");

// Type of the full propagation result, including output from actors
Expand Down Expand Up @@ -291,7 +290,7 @@ auto Acts::Propagator<S, N>::makeResult(
// Type of track parameters produced at the end of the propagation
using ReturnParameterType = StepperBoundTrackParameters;

static_assert(std::is_copy_constructible<ReturnParameterType>::value,
static_assert(std::copy_constructible<ReturnParameterType>,
"return track parameter type must be copy-constructible");

// Type of the full propagation result, including output from actors
Expand Down
12 changes: 7 additions & 5 deletions Core/include/Acts/Seeding/detail/CylindricalSpacePointGrid.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@
// License, v. 2.0. If a copy of the MPL was not distributed with this
// file, You can obtain one at https://mozilla.org/MPL/2.0/.

#include <concepts>

template <typename external_spacepoint_t>
Acts::CylindricalSpacePointGrid<external_spacepoint_t>
Acts::CylindricalSpacePointGridCreator::createGrid(
Expand Down Expand Up @@ -142,12 +144,12 @@ void Acts::CylindricalSpacePointGridCreator::fillGrid(
external_spacepoint_iterator_t spBegin,
external_spacepoint_iterator_t spEnd, Acts::Extent& rRangeSPExtent) {
using iterated_value_t =
typename std::iterator_traits<external_spacepoint_iterator_t>::value_type;
using iterated_t = typename std::remove_const<
typename std::remove_pointer<iterated_value_t>::type>::type;
static_assert(!std::is_pointer<iterated_value_t>::value,
typename std::iter_value_t<external_spacepoint_iterator_t>;
using iterated_t = typename std::remove_const_t<
typename std::remove_pointer_t<iterated_value_t>>;
static_assert(!std::is_pointer_v<iterated_value_t>,
"Iterator must contain pointers to space points");
static_assert(std::is_same<iterated_t, external_spacepoint_t>::value,
static_assert(std::same_as<iterated_t, external_spacepoint_t>,
"Iterator does not contain type this class was templated with");

if (!config.isInInternalUnits) {
Expand Down
2 changes: 2 additions & 0 deletions Core/include/Acts/Surfaces/ConvexPolygonBounds.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include <array>
#include <cmath>
#include <concepts>
#include <cstddef>
#include <exception>
#include <iosfwd>
Expand Down Expand Up @@ -54,6 +55,7 @@ class ConvexPolygonBoundsBase : public PlanarBounds {
/// @param vertices A collection of vertices.
/// throws a logic error if this is not the case
template <typename coll_t>
requires std::same_as<typename coll_t::value_type, Acts::Vector2>
static void convex_impl(const coll_t& vertices) noexcept(false);
};

Expand Down
5 changes: 2 additions & 3 deletions Core/include/Acts/Surfaces/ConvexPolygonBounds.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -10,14 +10,13 @@
#include "Acts/Surfaces/detail/BoundaryCheckHelper.hpp"
#include "Acts/Utilities/ThrowAssert.hpp"

#include <concepts>
#include <optional>

template <typename coll_t>
requires std::same_as<typename coll_t::value_type, Acts::Vector2>
void Acts::ConvexPolygonBoundsBase::convex_impl(
const coll_t& vertices) noexcept(false) {
static_assert(std::is_same<typename coll_t::value_type, Vector2>::value,
"Must be collection of Vector2");

const std::size_t N = vertices.size();
for (std::size_t i = 0; i < N; i++) {
std::size_t j = (i + 1) % N;
Expand Down
6 changes: 2 additions & 4 deletions Core/include/Acts/TrackFinding/CombinatorialKalmanFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <functional>
#include <limits>
#include <memory>
#include <ranges>
#include <string_view>
#include <type_traits>
#include <unordered_map>
Expand Down Expand Up @@ -357,10 +358,7 @@ class CombinatorialKalmanFilter {
const auto& [boundParams, jacobian, pathLength] = boundState;

trackStateCandidates.clear();
if constexpr (std::is_same_v<
typename std::iterator_traits<
source_link_iterator_t>::iterator_category,
std::random_access_iterator_tag>) {
if constexpr (std::ranges::random_access_range<source_link_iterator_t>) {
trackStateCandidates.reserve(std::distance(slBegin, slEnd));
}

Expand Down
3 changes: 2 additions & 1 deletion Core/include/Acts/TrackFitting/GlobalChiSquareFitter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
#include <limits>
#include <map>
#include <memory>
#include <type_traits>
#include <unordered_map>

namespace Acts::Experimental {
Expand Down Expand Up @@ -513,7 +514,7 @@ class Gx2Fitter {

/// The navigator has DirectNavigator type or not
static constexpr bool isDirectNavigator =
std::is_same<Gx2fNavigator, DirectNavigator>::value;
std::is_same_v<Gx2fNavigator, DirectNavigator>;

public:
Gx2Fitter(propagator_t pPropagator,
Expand Down
3 changes: 2 additions & 1 deletion Core/include/Acts/TrackFitting/KalmanFitter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#include <limits>
#include <map>
#include <memory>
#include <type_traits>

namespace Acts {

Expand Down Expand Up @@ -264,7 +265,7 @@ class KalmanFitter {

/// The navigator has DirectNavigator type or not
static constexpr bool isDirectNavigator =
std::is_same<KalmanNavigator, DirectNavigator>::value;
std::is_same_v<KalmanNavigator, DirectNavigator>;

public:
KalmanFitter(propagator_t pPropagator,
Expand Down
3 changes: 1 addition & 2 deletions Core/include/Acts/Utilities/Concepts.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,7 @@ concept same_as_any_of = (std::same_as<T, Ts> || ...);
/// @brief Concept that is equivalent to `is_nothrow_move_constructible`.
/// @todo Convert this to a "real" concept.
template <typename T>
concept nothrow_move_constructible =
std::is_nothrow_move_constructible<T>::value;
concept nothrow_move_constructible = std::is_nothrow_move_constructible_v<T>;

/// @brief Concept that is true if T is an arithmetic type.
template <typename T>
Expand Down
3 changes: 1 addition & 2 deletions Core/include/Acts/Utilities/FiniteStateMachine.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,8 +119,7 @@ class FiniteStateMachine {
/// Default constructor. The default state is taken to be the first in the
/// `States` template arguments
FiniteStateMachine()
: m_state(typename std::tuple_element<0, std::tuple<States...>>::type{}) {
}
: m_state(typename std::tuple_element_t<0, std::tuple<States...>>{}) {}

/// Constructor from an explicit state. The FSM is initialized to this state.
/// @param state Initial state for the FSM.
Expand Down
22 changes: 11 additions & 11 deletions Core/include/Acts/Utilities/GridBinFinder.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -6,20 +6,21 @@
// License, v. 2.0. If a copy of the MPL was not distributed with this
// file, You can obtain one at https://mozilla.org/MPL/2.0/.

#include <type_traits>

template <std::size_t DIM>
template <typename first_value_t, typename... vals>
void Acts::GridBinFinder<DIM>::storeValue(first_value_t&& fv,
vals&&... others) {
constexpr std::size_t N = sizeof...(vals);
static_assert(N < DIM);
/// Check the fist value is reasonable
using decayed_value_t = typename std::decay<first_value_t>::type;
if constexpr (std::is_same<int, decayed_value_t>::value) {
using decayed_value_t = typename std::decay_t<first_value_t>;
if constexpr (std::is_same_v<int, decayed_value_t>) {
/// if int -> value is positive
assert(fv >= 0);
m_values[DIM - N - 1ul] = fv;
} else if constexpr (std::is_same<std::pair<int, int>,
decayed_value_t>::value) {
} else if constexpr (std::is_same_v<std::pair<int, int>, decayed_value_t>) {
m_values[DIM - N - 1ul] = fv;
} else {
/// If vector of pairs -> also allow for empty vectors
Expand All @@ -41,12 +42,11 @@ std::array<std::pair<int, int>, DIM> Acts::GridBinFinder<DIM>::getSizePerAxis(
for (std::size_t i(0ul); i < DIM; ++i) {
output[i] = std::visit(
[&locPosition, i](const auto& val) -> std::pair<int, int> {
using value_t = typename std::decay<decltype(val)>::type;
if constexpr (std::is_same<int, value_t>::value) {
using value_t = typename std::decay_t<decltype(val)>;
if constexpr (std::is_same_v<int, value_t>) {
assert(val >= 0);
return std::make_pair(-val, val);
} else if constexpr (std::is_same<std::pair<int, int>,
value_t>::value) {
} else if constexpr (std::is_same_v<std::pair<int, int>, value_t>) {
return std::make_pair(-val.first, val.second);
} else {
assert(locPosition.size() > i);
Expand Down Expand Up @@ -82,9 +82,9 @@ bool Acts::GridBinFinder<DIM>::isGridCompatible(
std::size_t nBins = nLocBins[i];
bool isCompabile = std::visit(
[nBins](const auto& val) -> bool {
using value_t = typename std::decay<decltype(val)>::type;
if constexpr (std::is_same<int, value_t>::value ||
std::is_same<std::pair<int, int>, value_t>::value) {
using value_t = typename std::decay_t<decltype(val)>;
if constexpr (std::is_same_v<int, value_t> ||
std::is_same_v<std::pair<int, int>, value_t>) {
return true;
} else {
return val.size() == nBins;
Expand Down
6 changes: 2 additions & 4 deletions Core/include/Acts/Utilities/TransformRange.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,8 +148,7 @@ struct TransformRange {
template <typename Callable, typename iterator_t, bool force_const>
struct TransformRangeIterator {
private:
using internal_value_type =
typename std::iterator_traits<iterator_t>::value_type;
using internal_value_type = typename std::iter_value_t<iterator_t>;

using raw_value_type = std::remove_reference_t<decltype(Callable::apply(
std::declval<internal_value_type>()))>;
Expand All @@ -162,8 +161,7 @@ struct TransformRangeIterator {
std::conditional_t<force_const, std::add_const_t<raw_value_type>,
raw_value_type>;

using difference_type =
typename std::iterator_traits<iterator_t>::difference_type;
using difference_type = typename std::iter_difference_t<iterator_t>;
using pointer = std::remove_reference_t<value_type>*;
using reference = value_type&;
using iterator_category = std::forward_iterator_tag;
Expand Down
16 changes: 8 additions & 8 deletions Core/include/Acts/Utilities/detail/interpolation_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,14 +46,14 @@ struct can_interpolate {
static std::false_type point_type_test(...);

static const bool value =
std::is_same<std::true_type,
decltype(value_type_test<Value>(nullptr))>::value &&
std::is_same<std::true_type,
decltype(point_type_test<Point1>(nullptr))>::value &&
std::is_same<std::true_type,
decltype(point_type_test<Point2>(nullptr))>::value &&
std::is_same<std::true_type,
decltype(point_type_test<Point3>(nullptr))>::value;
std::is_same_v<std::true_type,
decltype(value_type_test<Value>(nullptr))> &&
std::is_same_v<std::true_type,
decltype(point_type_test<Point1>(nullptr))> &&
std::is_same_v<std::true_type,
decltype(point_type_test<Point2>(nullptr))> &&
std::is_same_v<std::true_type,
decltype(point_type_test<Point3>(nullptr))>;
};

/// @brief concept equivalent to `can_interpolate`
Expand Down
10 changes: 4 additions & 6 deletions Examples/Io/Csv/include/ActsExamples/Io/Csv/CsvInputOutput.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -273,9 +273,8 @@ class NamedTupleDsvWriter {

/// Append a record to the file.
void append(const NamedTuple& record) {
append_impl(record,
std::make_index_sequence<
std::tuple_size<typename NamedTuple::Tuple>::value>{});
append_impl(record, std::make_index_sequence<
std::tuple_size_v<typename NamedTuple::Tuple>>{});
}

private:
Expand Down Expand Up @@ -548,8 +547,7 @@ inline bool NamedTupleDsvReader<Delimiter, NamedTuple>::read(
std::to_string(m_reader.num_lines()));
}
// convert to tuple
parse_record(record,
std::make_index_sequence<std::tuple_size<Tuple>::value>{});
parse_record(record, std::make_index_sequence<std::tuple_size_v<Tuple>>{});
return true;
}

Expand All @@ -572,7 +570,7 @@ inline bool NamedTupleDsvReader<Delimiter, NamedTuple>::read(
template <char Delimiter, typename NamedTuple>
inline void NamedTupleDsvReader<Delimiter, NamedTuple>::use_default_columns() {
// assume row content is identical in content and order to the tuple
m_num_columns = std::tuple_size<Tuple>::value;
m_num_columns = std::tuple_size_v<Tuple>;
for (std::size_t i = 0; i < m_tuple_column_map.size(); ++i) {
m_tuple_column_map[i] = i;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -155,7 +155,7 @@ nlohmann::json GeometryHierarchyMapJsonConverter<value_t, decorator_t>::toJson(
for (std::size_t i = 0; i < container.size(); ++i) {
auto entry = encodeIdentifier(container.idAt(i));
auto value_json = nlohmann::json(container.valueAt(i));
if constexpr (!std::is_same<decorator_t, void>::value) {
if constexpr (!std::is_same_v<decorator_t, void>) {
decorateJson(decorator, container.valueAt(i), value_json);
}
entry["value"] = std::move(value_json);
Expand Down
2 changes: 1 addition & 1 deletion Tests/UnitTests/Core/EventData/TrackStatePropMaskTests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ BOOST_AUTO_TEST_CASE(BitmaskOperators) {
BOOST_CHECK(!ACTS_CHECK_BIT(bs4, PM::Filtered));

auto cnv = [](auto a) -> std::bitset<8> {
return static_cast<std::underlying_type<PM>::type>(a);
return static_cast<std::underlying_type_t<PM>>(a);
};

BOOST_CHECK(cnv(PM::All).all()); // all ones
Expand Down
Loading

0 comments on commit da9b89c

Please sign in to comment.