Skip to content

Commit

Permalink
refactor!: Rename ActsSymMatrix -> ActsSquareMatrix (#2387)
Browse files Browse the repository at this point in the history
A square matrix has the same number of rows and columns.
A symmetric matrix is a square matrix with transposition symmetry, i.e., `A.transpose() == A`.

Since we don't impose transposition symmetry when initializing an `ActsSymMatrix`, I propose to rename it `ActsSquareMatrix`.
  • Loading branch information
felix-russo authored Aug 22, 2023
1 parent c3f99be commit 7f67ffd
Show file tree
Hide file tree
Showing 139 changed files with 452 additions and 437 deletions.
10 changes: 5 additions & 5 deletions Core/include/Acts/Definitions/Algebra.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ template <unsigned int kRows, unsigned int kCols>
using ActsMatrix = Eigen::Matrix<ActsScalar, kRows, kCols>;

template <unsigned int kSize>
using ActsSymMatrix = Eigen::Matrix<ActsScalar, kSize, kSize>;
using ActsSquareMatrix = Eigen::Matrix<ActsScalar, kSize, kSize>;

using ActsDynamicVector = Eigen::Matrix<ActsScalar, Eigen::Dynamic, 1>;

Expand All @@ -79,10 +79,10 @@ using Vector2 = ActsVector<2>;
using Vector3 = ActsVector<3>;
using Vector4 = ActsVector<4>;

// symmetric matrices e.g. for coordinate covariance matrices
using SymMatrix2 = ActsSymMatrix<2>;
using SymMatrix3 = ActsSymMatrix<3>;
using SymMatrix4 = ActsSymMatrix<4>;
// square matrices e.g. for coordinate covariance matrices
using SquareMatrix2 = ActsSquareMatrix<2>;
using SquareMatrix3 = ActsSquareMatrix<3>;
using SquareMatrix4 = ActsSquareMatrix<4>;

// pure translation transformations
using Translation2 = Eigen::Translation<ActsScalar, 2>;
Expand Down
4 changes: 2 additions & 2 deletions Core/include/Acts/Definitions/TrackParametrization.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,14 +116,14 @@ static_assert(eFreeDir2 == eFreeDir0 + 2u, "Direction must be continuous");
// Shorthand vector/matrix types related to bound track parameters.
using BoundVector = ActsVector<eBoundSize>;
using BoundMatrix = ActsMatrix<eBoundSize, eBoundSize>;
using BoundSymMatrix = ActsSymMatrix<eBoundSize>;
using BoundSquareMatrix = ActsSquareMatrix<eBoundSize>;
// Mapping from bound track parameters.
using BoundToFreeMatrix = ActsMatrix<eFreeSize, eBoundSize>;

// Shorthand vector/matrix types related to free track parameters.
using FreeVector = ActsVector<eFreeSize>;
using FreeMatrix = ActsMatrix<eFreeSize, eFreeSize>;
using FreeSymMatrix = ActsSymMatrix<eFreeSize>;
using FreeSquareMatrix = ActsSquareMatrix<eFreeSize>;
// Mapping from free track parameters.
using FreeToBoundMatrix = ActsMatrix<eBoundSize, eFreeSize>;
using FreeToPathMatrix = ActsMatrix<1, eFreeSize>;
Expand Down
4 changes: 2 additions & 2 deletions Core/include/Acts/EventData/GenericBoundTrackParameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class GenericBoundTrackParameters {
public:
using Scalar = ActsScalar;
using ParametersVector = BoundVector;
using CovarianceMatrix = BoundSymMatrix;
using CovarianceMatrix = BoundSquareMatrix;

/// Construct from a parameters vector on the surface and particle charge.
///
Expand Down Expand Up @@ -240,7 +240,7 @@ class GenericBoundTrackParameters {

private:
BoundVector m_params;
std::optional<BoundSymMatrix> m_cov;
std::optional<BoundSquareMatrix> m_cov;
/// reference surface
std::shared_ptr<const Surface> m_surface;
// TODO use [[no_unique_address]] once we switch to C++20
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class GenericCurvilinearTrackParameters
public:
using Scalar = ActsScalar;
using ParametersVector = BoundVector;
using CovarianceMatrix = BoundSymMatrix;
using CovarianceMatrix = BoundSquareMatrix;

/// Construct from four-position, direction, absolute momentum, and charge.
///
Expand Down
4 changes: 2 additions & 2 deletions Core/include/Acts/EventData/GenericFreeTrackParameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class GenericFreeTrackParameters {
public:
using Scalar = ActsScalar;
using ParametersVector = FreeVector;
using CovarianceMatrix = FreeSymMatrix;
using CovarianceMatrix = FreeSquareMatrix;

/// Construct from a parameters vector and particle charge.
///
Expand Down Expand Up @@ -188,7 +188,7 @@ class GenericFreeTrackParameters {

private:
FreeVector m_params;
std::optional<FreeSymMatrix> m_cov;
std::optional<FreeSquareMatrix> m_cov;
// TODO use [[no_unique_address]] once we switch to C++20
charge_t m_chargeInterpreter;

Expand Down
2 changes: 1 addition & 1 deletion Core/include/Acts/EventData/Measurement.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class Measurement {
/// Vector type containing for measured parameter values.
using ParametersVector = ActsVector<kSize>;
/// Matrix type for the measurement covariance.
using CovarianceMatrix = ActsSymMatrix<kSize>;
using CovarianceMatrix = ActsSquareMatrix<kSize>;
/// Vector type containing all parameters in the same space.
using FullParametersVector = ActsVector<kFullSize>;
using ProjectionMatrix = ActsMatrix<kSize, kFullSize>;
Expand Down
22 changes: 12 additions & 10 deletions Core/include/Acts/EventData/MultiComponentBoundTrackParameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ template <typename charge_t>
class MultiComponentBoundTrackParameters {
using SingleParameters = GenericBoundTrackParameters<charge_t>;

std::vector<std::tuple<double, BoundVector, std::optional<BoundSymMatrix>>>
std::vector<std::tuple<double, BoundVector, std::optional<BoundSquareMatrix>>>
m_components;
std::shared_ptr<const Surface> m_surface;

Expand Down Expand Up @@ -73,9 +73,10 @@ class MultiComponentBoundTrackParameters {
const std::vector<std::tuple<double, BoundVector, covariance_t>>& cmps,
ActsScalar q)
: m_surface(std::move(surface)), m_chargeInterpreter(std::abs(q)) {
static_assert(std::is_same_v<BoundSymMatrix, covariance_t> ||
std::is_same_v<std::optional<BoundSymMatrix>, covariance_t>);
if constexpr (std::is_same_v<BoundSymMatrix, covariance_t>) {
static_assert(
std::is_same_v<BoundSquareMatrix, covariance_t> ||
std::is_same_v<std::optional<BoundSquareMatrix>, covariance_t>);
if constexpr (std::is_same_v<BoundSquareMatrix, covariance_t>) {
for (const auto& [weight, params, cov] : cmps) {
m_components.push_back({weight, params, cov});
}
Expand All @@ -91,9 +92,10 @@ class MultiComponentBoundTrackParameters {
std::shared_ptr<const Surface> surface,
const std::vector<std::tuple<double, BoundVector, covariance_t>>& cmps)
: m_surface(std::move(surface)) {
static_assert(std::is_same_v<BoundSymMatrix, covariance_t> ||
std::is_same_v<std::optional<BoundSymMatrix>, covariance_t>);
if constexpr (std::is_same_v<BoundSymMatrix, covariance_t>) {
static_assert(
std::is_same_v<BoundSquareMatrix, covariance_t> ||
std::is_same_v<std::optional<BoundSquareMatrix>, covariance_t>);
if constexpr (std::is_same_v<BoundSquareMatrix, covariance_t>) {
for (const auto& [weight, params, cov] : cmps) {
m_components.push_back({weight, params, cov});
}
Expand All @@ -117,7 +119,7 @@ class MultiComponentBoundTrackParameters {
/// parameter.
MultiComponentBoundTrackParameters(
std::shared_ptr<const Surface> surface, const BoundVector& params,
ActsScalar q, std::optional<BoundSymMatrix> cov = std::nullopt)
ActsScalar q, std::optional<BoundSquareMatrix> cov = std::nullopt)
: m_surface(std::move(surface)), m_chargeInterpreter(std::abs(q)) {
m_components.push_back({1., params, std::move(cov)});
}
Expand All @@ -134,7 +136,7 @@ class MultiComponentBoundTrackParameters {
std::enable_if_t<std::is_default_constructible_v<T>, int> = 0>
MultiComponentBoundTrackParameters(
std::shared_ptr<const Surface> surface, const BoundVector& params,
std::optional<BoundSymMatrix> cov = std::nullopt)
std::optional<BoundSquareMatrix> cov = std::nullopt)
: m_surface(std::move(surface)) {
m_components.push_back({1., params, std::move(cov)});
}
Expand Down Expand Up @@ -163,7 +165,7 @@ class MultiComponentBoundTrackParameters {
std::get<double>(m_components[i]),
SingleParameters(
m_surface, std::get<BoundVector>(m_components[i]),
std::get<std::optional<BoundSymMatrix>>(m_components[i])));
std::get<std::optional<BoundSquareMatrix>>(m_components[i])));
}

/// Parameters vector.
Expand Down
6 changes: 3 additions & 3 deletions Core/include/Acts/EventData/MultiTrajectoryBackendConcept.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ concept CommonMultiTrajectoryBackend = requires(const T& cv, HashedString key,

{
cv.template measurementCovariance_impl<2>(istate)
} -> std::same_as<Eigen::Map<const ActsSymMatrix<2>>>;
} -> std::same_as<Eigen::Map<const ActsSquareMatrix<2>>>;

{ cv.has_impl(key, istate) } -> std::same_as<bool>;

Expand All @@ -80,7 +80,7 @@ concept ConstMultiTrajectoryBackend = CommonMultiTrajectoryBackend<T> &&

{
v.template measurementCovariance_impl<2>(istate)
} -> std::same_as<Eigen::Map<const ActsSymMatrix<2>>>;
} -> std::same_as<Eigen::Map<const ActsSquareMatrix<2>>>;
};

template <typename T>
Expand All @@ -100,7 +100,7 @@ concept MutableMultiTrajectoryBackend = CommonMultiTrajectoryBackend<T> &&

{
v.template measurementCovariance_impl<2>(istate)
} -> std::same_as<Eigen::Map<ActsSymMatrix<2>>>;
} -> std::same_as<Eigen::Map<ActsSquareMatrix<2>>>;

{ v.addTrackState_impl() } -> std::same_as<TrackIndexType>;

Expand Down
4 changes: 2 additions & 2 deletions Core/include/Acts/EventData/TrackParametersConcept.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ struct BoundTrackParametersConceptImpl {
std::is_convertible_v<ReturnTypeParameters<T>, BoundVector>;
constexpr static bool hasMethodCovariance =
std::is_convertible_v<ReturnTypeCovariance<T>,
std::optional<BoundSymMatrix>>;
std::optional<BoundSquareMatrix>>;
constexpr static bool hasMethodFourPositionFromContext =
identical_to<Vector4, ReturnTypeFourPositionFromContext, const T>;
constexpr static bool hasMethodPositionFromContext =
Expand Down Expand Up @@ -127,7 +127,7 @@ struct FreeTrackParametersConceptImpl {
std::is_convertible_v<ReturnTypeParameters<T>, FreeVector>;
constexpr static bool hasMethodCovariance =
std::is_convertible_v<ReturnTypeCovariance<T>,
std::optional<FreeSymMatrix>>;
std::optional<FreeSquareMatrix>>;
constexpr static bool hasMethodFourPosition =
identical_to<Vector4, ReturnTypeFourPosition, const T>;
constexpr static bool hasMethodPosition =
Expand Down
4 changes: 2 additions & 2 deletions Core/include/Acts/EventData/TrackStateProxyConcept.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,10 +33,10 @@ using ConstParameters = Eigen::Map<const BoundVector>;
using ConstCovariance = Eigen::Map<const BoundMatrix>;

using Measurement = Eigen::Map<ActsVector<2>>;
using MeasurementCovariance = Eigen::Map<ActsSymMatrix<2>>;
using MeasurementCovariance = Eigen::Map<ActsSquareMatrix<2>>;

using ConstMeasurement = Eigen::Map<const ActsVector<2>>;
using ConstMeasurementCovariance = Eigen::Map<const ActsSymMatrix<2>>;
using ConstMeasurementCovariance = Eigen::Map<const ActsSquareMatrix<2>>;

using DynamicMeasurement =
Eigen::Map<Eigen::Matrix<Covariance::Scalar, Eigen::Dynamic, 1,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,8 @@ struct CorrectedFreeToBoundTransformer {
/// @param geoContext The geometry context
/// @param navDir The navigation direction
/// @param logger The logger
std::optional<std::tuple<BoundVector, BoundSymMatrix>> operator()(
const FreeVector& freeParams, const FreeSymMatrix& freeCovariance,
std::optional<std::tuple<BoundVector, BoundSquareMatrix>> operator()(
const FreeVector& freeParams, const FreeSquareMatrix& freeCovariance,
const Surface& surface, const GeometryContext& geoContext,
Direction navDir = Direction::Forward,
const Logger& logger = getDummyLogger()) const;
Expand Down
2 changes: 1 addition & 1 deletion Core/include/Acts/EventData/detail/PrintParameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ namespace detail {
/// @param cov Optional bound parameters covariance matrix
void printBoundParameters(std::ostream& os, const Surface& surface,
const BoundVector& params,
const BoundSymMatrix* cov = nullptr);
const BoundSquareMatrix* cov = nullptr);

/// Print free track parameters content to the output stream.
///
Expand Down
10 changes: 5 additions & 5 deletions Core/include/Acts/Propagator/AtlasStepper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ namespace Acts {
class AtlasStepper {
public:
using Jacobian = BoundMatrix;
using Covariance = BoundSymMatrix;
using Covariance = BoundSquareMatrix;
using BoundState = std::tuple<BoundTrackParameters, Jacobian, double>;
using CurvilinearState =
std::tuple<CurvilinearTrackParameters, Jacobian, double>;
Expand Down Expand Up @@ -94,7 +94,7 @@ class AtlasStepper {
// prepare the jacobian if we have a covariance
if (pars.covariance()) {
// copy the covariance matrix
covariance = new BoundSymMatrix(*pars.covariance());
covariance = new BoundSquareMatrix(*pars.covariance());
covTransport = true;
useJacobian = true;
const auto transform = pars.referenceSurface().referenceFrame(
Expand Down Expand Up @@ -310,8 +310,8 @@ class AtlasStepper {
/// @param [in] surface Reset state will be on this surface
/// @param [in] stepSize Step size
void resetState(
State& state, const BoundVector& boundParams, const BoundSymMatrix& cov,
const Surface& surface,
State& state, const BoundVector& boundParams,
const BoundSquareMatrix& cov, const Surface& surface,
const double stepSize = std::numeric_limits<double>::max()) const {
// Update the stepping state
update(state,
Expand Down Expand Up @@ -697,7 +697,7 @@ class AtlasStepper {
state.pVector[34] = Bz3 * boundParams[eBoundLoc0]; // dZ/
}

state.covariance = new BoundSymMatrix(covariance);
state.covariance = new BoundSquareMatrix(covariance);
state.covTransport = true;
state.useJacobian = true;

Expand Down
8 changes: 4 additions & 4 deletions Core/include/Acts/Propagator/CovarianceTransport.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

namespace Acts {

using VariantCovariance = std::variant<BoundSymMatrix, FreeSymMatrix>;
using VariantCovariance = std::variant<BoundSquareMatrix, FreeSquareMatrix>;

using VariantTransportJacobian =
std::variant<BoundMatrix, BoundToFreeMatrix, FreeToBoundMatrix, FreeMatrix>;
Expand Down Expand Up @@ -67,7 +67,7 @@ struct CovarianceCache {
/// jacobian between bound and free parametrisation.
CovarianceCache(const GeometryContext& gctx, const Surface& surface,
const Vector3& position, const BoundVector& boundParameters,
const BoundSymMatrix& boundCovariance);
const BoundSquareMatrix& boundCovariance);

/// Constructor from curvilinear
///
Expand All @@ -79,15 +79,15 @@ struct CovarianceCache {
/// a bound matrix, remember the surface & establish the
/// jacobian between bound and free parametrisation.
CovarianceCache(const Vector3& position, const Vector3& direction,
const BoundSymMatrix& boundCovariance);
const BoundSquareMatrix& boundCovariance);

/// Construction from free
///
/// @param freeParameters The free parameters
/// @param freeCovariance The free covariance to be propagated
///
CovarianceCache(const FreeVector& freeParameters,
const FreeSymMatrix& freeCovariance);
const FreeSquareMatrix& freeCovariance);
};

/// Transport the covariance to a new (surface) bound definition
Expand Down
8 changes: 4 additions & 4 deletions Core/include/Acts/Propagator/EigenStepper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class EigenStepper {
public:
/// Jacobian, Covariance and State definitions
using Jacobian = BoundMatrix;
using Covariance = BoundSymMatrix;
using Covariance = BoundSquareMatrix;
using BoundState = std::tuple<BoundTrackParameters, Jacobian, double>;
using CurvilinearState =
std::tuple<CurvilinearTrackParameters, Jacobian, double>;
Expand Down Expand Up @@ -92,7 +92,7 @@ class EigenStepper {
const auto& surface = par.referenceSurface();
// set the covariance transport flag to true and copy
covTransport = true;
cov = BoundSymMatrix(*par.covariance());
cov = BoundSquareMatrix(*par.covariance());
jacToGlobal = surface.boundToFreeJacobian(gctx, par.parameters());
}
}
Expand Down Expand Up @@ -172,8 +172,8 @@ class EigenStepper {
/// @param [in] surface The reference surface of the bound parameters
/// @param [in] stepSize Step size
void resetState(
State& state, const BoundVector& boundParams, const BoundSymMatrix& cov,
const Surface& surface,
State& state, const BoundVector& boundParams,
const BoundSquareMatrix& cov, const Surface& surface,
const double stepSize = std::numeric_limits<double>::max()) const;

/// Get the field for the stepping, it checks first if the access is still
Expand Down
2 changes: 1 addition & 1 deletion Core/include/Acts/Propagator/EigenStepper.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ auto Acts::EigenStepper<E, A>::makeState(
template <typename E, typename A>
void Acts::EigenStepper<E, A>::resetState(State& state,
const BoundVector& boundParams,
const BoundSymMatrix& cov,
const BoundSquareMatrix& cov,
const Surface& surface,
const double stepSize) const {
// Update the stepping state
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 @@ -346,8 +346,8 @@ class MultiEigenStepperLoop
/// @param [in] surface The reference surface of the bound parameters
/// @param [in] stepSize Step size
void resetState(
State& state, const BoundVector& boundParams, const BoundSymMatrix& cov,
const Surface& surface,
State& state, const BoundVector& boundParams,
const BoundSquareMatrix& cov, const Surface& surface,
const double stepSize = std::numeric_limits<double>::max()) const {
for (auto& component : state.components) {
SingleStepper::resetState(component.state, boundParams, cov, surface,
Expand Down
Loading

0 comments on commit 7f67ffd

Please sign in to comment.