ECCE @ EIC Software
Reference for
ECCE @ EIC
simulation and reconstruction software on GitHub
|
These functions perform the transport of a covariance matrix using given Jacobians. The required data is provided by the stepper object with some additional data. Since this is a purely algebraic problem the calculations are identical for StraightLineStepper
and EigenStepper
. As a consequence the methods can be located in a seperate file.
More...
Namespaces | |
namespace | VerticesHelper |
Helper method for set of vertices for polyhedrons drawing and inside/outside checks. | |
Classes | |
struct | covariance_helper |
check and correct covariance matrix More... | |
struct | visit_measurement_callable |
class | KalmanFitterErrorCategory |
struct | DefaultGeometryIdGetter |
Uniform access to geometry identifiers for different types. More... | |
struct | abort_list_impl< first, others...> |
struct | abort_list_impl< last > |
This is the check call on the a last of all conditions. More... | |
struct | abort_list_impl<> |
This is the empty call list - never abort. More... | |
struct | action_list_impl< first, others...> |
struct | action_list_impl< last > |
struct | action_list_impl<> |
The empty action list call implementation. More... | |
struct | VoidAuctioneer |
Auctioneer that takes all extensions as valid that make a valid bid. More... | |
struct | FirstValidAuctioneer |
Auctioneer that states only the first one that makes a valid bid. More... | |
struct | HighestValidAuctioneer |
Auctioneer that makes only the highest bidding extension valid. If multiple elements have the same int, the first one with this value is picked. More... | |
struct | LoopProtection |
struct | PointwiseMaterialInteraction |
Struct to handle pointwise material interaction. More... | |
struct | stepper_extension_list_impl |
struct | stepper_extension_list_impl< 0u > |
Template specialized list call implementation. More... | |
struct | Step |
the step information for More... | |
struct | SteppingLogger |
a step length logger for debugging the stepping More... | |
struct | VoidNavigator |
The void navigator struct as a default navigator. More... | |
struct | VolumeMaterialInteraction |
Struct to handle volume material interaction. More... | |
class | EigenStepperErrorCategory |
class | PropagatorErrorCategory |
struct | FacesHelper |
Helper for writing out faces for polyhedron representation. More... | |
class | CombinatorialKalmanFilterErrorCategory |
class | NeighborHoodIndices |
exception | Axis< AxisType::Equidistant, bdt > |
calculate bin indices for an equidistant binning More... | |
exception | Axis< AxisType::Variable, bdt > |
calculate bin indices for a variable binning More... | |
struct | Extendable |
class | Grid |
class for describing a regular multi-dimensional grid More... | |
class | GlobalNeighborHoodIndices |
struct | grid_helper_impl |
struct | grid_helper_impl< 0u > |
struct | grid_helper |
helper functions for grid-related operations More... | |
struct | can_interpolate |
check types for requirements needed by interpolation More... | |
struct | get_dimension |
determine number of dimension from power of 2 More... | |
struct | result_type_extractor |
struct | action_type_extractor |
struct | RealQuadraticEquation |
struct | BoundParameterTraits< BoundParametersIndices::eBoundLoc0 > |
struct | BoundParameterTraits< BoundParametersIndices::eBoundLoc1 > |
struct | BoundParameterTraits< BoundParametersIndices::eBoundPhi > |
struct | BoundParameterTraits< BoundParametersIndices::eBoundTheta > |
struct | BoundParameterTraits< BoundParametersIndices::eBoundQOverP > |
struct | BoundParameterTraits< BoundParametersIndices::eBoundTime > |
struct | nonesuch |
struct | detector |
struct | detector< Default, std::void_t< Op< Args...> >, Op, Args...> |
class | VertexingErrorCategory |
struct | SpacePointParameters |
Storage container for variables related to the calculation of space points. More... | |
Typedefs | |
using | EquidistantAxis = Axis< AxisType::Equidistant > |
using | VariableAxis = Axis< AxisType::Variable > |
template<typename T > | |
using | result_type_t = typename result_type_extractor::extractor_impl< T > |
template<typename T > | |
using | action_type_t = typename action_type_extractor::extractor_impl< T > |
Enumerations | |
enum | AxisBoundaryType |
enum | AxisType |
Enum which determines the binning type of the axis. More... | |
Functions | |
std::tuple< BoundParameters, BoundMatrix, double > | boundState (std::reference_wrapper< const GeometryContext > geoContext, BoundSymMatrix &covarianceMatrix, BoundMatrix &jacobian, FreeMatrix &transportJacobian, FreeVector &derivatives, BoundToFreeMatrix &jacobianLocalToGlobal, const FreeVector ¶meters, bool covTransport, double accumulatedPath, const Surface &surface) |
It does not check if the transported state is at the surface, this needs to be guaranteed by the propagator. | |
std::tuple < CurvilinearParameters, BoundMatrix, double > | curvilinearState (BoundSymMatrix &covarianceMatrix, BoundMatrix &jacobian, FreeMatrix &transportJacobian, FreeVector &derivatives, BoundToFreeMatrix &jacobianLocalToGlobal, const FreeVector ¶meters, bool covTransport, double accumulatedPath) |
This creates a curvilinear state. | |
void | covarianceTransport (std::reference_wrapper< const GeometryContext > geoContext, BoundSymMatrix &covarianceMatrix, BoundMatrix &jacobian, FreeMatrix &transportJacobian, FreeVector &derivatives, BoundToFreeMatrix &jacobianLocalToGlobal, const FreeVector ¶meters, const Surface &surface) |
Method for on-demand transport of the covariance to a new frame at current position in parameter space. | |
void | covarianceTransport (BoundSymMatrix &covarianceMatrix, BoundMatrix &jacobian, FreeMatrix &transportJacobian, FreeVector &derivatives, BoundToFreeMatrix &jacobianLocalToGlobal, const Vector3D &direction) |
Method for on-demand transport of the covariance to a new frame at current position in parameter space. | |
template<typename stepper_t > | |
Acts::Intersection::Status | updateSingleSurfaceStatus (const stepper_t &stepper, typename stepper_t::State &state, const Surface &surface, const BoundaryCheck &bcheck) |
template<typename stepper_t , typename object_intersection_t > | |
void | updateSingleStepSize (typename stepper_t::State &state, const object_intersection_t &oIntersection, bool release=true) |
template<typename T > | |
T | wrap_periodic (T value, T start, T range) |
Wrap a periodic value back into the nominal range. | |
template<typename T > | |
T | radian_pos (T x) |
Calculate the equivalent angle in the [0, 2*pi) range. | |
template<typename T > | |
T | radian_sym (T x) |
Calculate the equivalent angle in the [-pi, pi) range. | |
template<typename T > | |
std::pair< T, T > | ensureThetaBounds (T phi, T theta) |
double | roundWithPrecision (double val, int precision) |
BoundState | boundState (std::reference_wrapper< const GeometryContext > geoContext, Covariance &covarianceMatrix, Jacobian &jacobian, FreeMatrix &transportJacobian, FreeVector &derivatives, BoundToFreeMatrix &jacobianLocalToGlobal, const FreeVector ¶meters, bool covTransport, double accumulatedPath, const Surface &surface) |
CurvilinearState | curvilinearState (Covariance &covarianceMatrix, Jacobian &jacobian, FreeMatrix &transportJacobian, FreeVector &derivatives, BoundToFreeMatrix &jacobianLocalToGlobal, const FreeVector ¶meters, bool covTransport, double accumulatedPath) |
void | covarianceTransport (Covariance &covarianceMatrix, Jacobian &jacobian, FreeMatrix &transportJacobian, FreeVector &derivatives, BoundToFreeMatrix &jacobianLocalToGlobal, const Vector3D &direction) |
void | covarianceTransport (std::reference_wrapper< const GeometryContext > geoContext, Covariance &covarianceMatrix, Jacobian &jacobian, FreeMatrix &transportJacobian, FreeVector &derivatives, BoundToFreeMatrix &jacobianLocalToGlobal, const FreeVector ¶meters, const Surface &surface) |
double | differenceOfClustersChecked (const Vector3D &pos1, const Vector3D &pos2, const Vector3D &posVertex, const double maxDistance, const double maxAngleTheta2, const double maxAnglePhi2) |
Calculates (Delta theta)^2 + (Delta phi)^2 between two clusters. | |
std::pair< Vector2D, Vector2D > | findLocalTopAndBottomEnd (const Vector2D &local, const CartesianSegmentation *segment) |
This function finds the top and bottom end of a detector segment in local coordinates. | |
double | calcPerpendicularProjection (const Vector3D &a, const Vector3D &c, const Vector3D &q, const Vector3D &r) |
Calculates a space point whithout using the vertex. | |
bool | recoverSpacePoint (SpacePointParameters &spaPoPa, double stripLengthGapTolerance) |
This function tests if a space point can be estimated by a more tolerant treatment of construction. In fact, this function indirectly allows shifts of the vertex. | |
bool | calculateSpacePoint (const std::pair< Vector3D, Vector3D > &stripEnds1, const std::pair< Vector3D, Vector3D > &stripEnds2, const Vector3D &posVertex, SpacePointParameters &spaPoPa, const double stripLengthTolerance) |
This function performs a straight forward calculation of a space point and returns whether it was succesful or not. | |
Variables | |
static const double | _helper [9] = {0., 1., 0., 1., 0., 0., 0., 0., -1.} |
template<typename T , typename propagator_state_t , typename stepper_t > | |
constexpr bool | action_signature_check_v |
template<bool... values> | |
constexpr bool | all_of_v = all_of<values...>::value |
template<bool... values> | |
constexpr bool | any_of_v = any_of<values...>::value |
template<typename... Args> | |
constexpr bool | has_duplicates_v = has_duplicates<Args...>::value |
constexpr auto | type_collector |
template<typename helper , typename... items> | |
constexpr auto | type_collector_t |
template<typename T > | |
constexpr bool | has_result_type_v |
template<typename T > | |
constexpr bool | has_action_type_v |
These functions perform the transport of a covariance matrix using given Jacobians. The required data is provided by the stepper object with some additional data. Since this is a purely algebraic problem the calculations are identical for StraightLineStepper
and EigenStepper
. As a consequence the methods can be located in a seperate file.
The following operators have to be inplemented in order to satisfy as an actor in the propagation
clang-format off
clang-format off
using Acts::detail::action_type_t = typedef typename action_type_extractor::extractor_impl<T> |
Meta function which gets the action for an aborter
T | The type to extract from |
Definition at line 107 of file type_collector.hpp.
View newest version in sPHENIX GitHub at line 107 of file type_collector.hpp
using Acts::detail::EquidistantAxis = typedef Axis<AxisType::Equidistant> |
Definition at line 40 of file AxisFwd.hpp.
View newest version in sPHENIX GitHub at line 40 of file AxisFwd.hpp
using Acts::detail::result_type_t = typedef typename result_type_extractor::extractor_impl<T> |
Meta function which gets the result type from an action
T | The type to extract from |
Definition at line 92 of file type_collector.hpp.
View newest version in sPHENIX GitHub at line 92 of file type_collector.hpp
using Acts::detail::VariableAxis = typedef Axis<AxisType::Variable> |
Definition at line 41 of file AxisFwd.hpp.
View newest version in sPHENIX GitHub at line 41 of file AxisFwd.hpp
Enum which determines how the axis handle its outer boundaries possible values values
Definition at line 21 of file AxisFwd.hpp.
View newest version in sPHENIX GitHub at line 21 of file AxisFwd.hpp
Enum which determines the binning type of the axis.
Definition at line 24 of file AxisFwd.hpp.
View newest version in sPHENIX GitHub at line 24 of file AxisFwd.hpp
std::tuple<BoundParameters, BoundMatrix, double> Acts::detail::boundState | ( | std::reference_wrapper< const GeometryContext > | geoContext, |
BoundSymMatrix & | covarianceMatrix, | ||
BoundMatrix & | jacobian, | ||
FreeMatrix & | transportJacobian, | ||
FreeVector & | derivatives, | ||
BoundToFreeMatrix & | jacobianLocalToGlobal, | ||
const FreeVector & | parameters, | ||
bool | covTransport, | ||
double | accumulatedPath, | ||
const Surface & | surface | ||
) |
It does not check if the transported state is at the surface, this needs to be guaranteed by the propagator.
Create and return the bound state at the current position
[in] | geoContext | The geometry context |
[in,out] | covarianceMatrix | The covariance matrix of the state |
[in,out] | jacobian | Full jacobian since the last reset |
[in,out] | transportJacobian | Global jacobian since the last reset |
[in,out] | derivatives | Path length derivatives of the free, nominal parameters |
[in,out] | jacobianLocalToGlobal | Projection jacobian of the last bound parametrisation to free parameters |
[in] | parameters | Free, nominal parametrisation |
[in] | covTransport | Decision whether the covariance transport should be performed |
[in] | accumulatedPath | Propagated distance |
[in] | surface | Target surface on which the state is represented |
Referenced by Acts::CombinatorialKalmanFilter< propagator_t, updater_t, smoother_t, source_link_selector_t, branch_stopper_t, calibrator_t, input_converter_t, output_converter_t >::Actor< source_link_t, parameters_t >::addHoleState(), Acts::CombinatorialKalmanFilter< propagator_t, updater_t, smoother_t, source_link_selector_t, branch_stopper_t, calibrator_t, input_converter_t, output_converter_t >::Actor< source_link_t, parameters_t >::addSourcelinkState(), Acts::Test::BOOST_AUTO_TEST_CASE(), Acts::StraightLineStepper::boundState(), Acts::EigenStepper< bfield_t, extensionlist_t, auctioneer_t >::boundState(), Acts::CombinatorialKalmanFilter< propagator_t, updater_t, smoother_t, source_link_selector_t, branch_stopper_t, calibrator_t, input_converter_t, output_converter_t >::Actor< source_link_t, parameters_t >::filter(), and Acts::Test::StepWiseActor::operator()().
|
static |
Definition at line 217 of file CovarianceEngine.cpp.
View newest version in sPHENIX GitHub at line 217 of file CovarianceEngine.cpp
References kdfinder::abs(), charge, covarianceTransport(), Acts::eFreeDir0, Acts::eFreePos0, Acts::eFreeQOverP, Acts::eFreeTime, Acts::Surface::getSharedPtr(), momentum, and Acts::VectorHelpers::time().
double Acts::detail::calcPerpendicularProjection | ( | const Vector3D & | a, |
const Vector3D & | c, | ||
const Vector3D & | q, | ||
const Vector3D & | r | ||
) |
Calculates a space point whithout using the vertex.
a | vector to the top end of the first SDE |
c | vector to the top end of the second SDE |
q | vector from the bottom to the top end of the first SDE |
r | vector from the bottom to the top end of the second SDE |
This approach assumes that no vertex is available. This option aims to approximate the space points from cosmic data. The underlying assumption is that the best point is given by the closest distance between both lines describing the SDEs. The point x on the first SDE is parametrized as a + lambda0 * q with the top end a of the strip and the vector q = a - b(ottom end of the strip). An analogous parametrization is performed of the second SDE with y = c + lambda1 * r. x get resolved by resolving lambda0 from the condition that |x-y| is the shortest distance between two skew lines.
Definition at line 135 of file DoubleHitSpacePointBuilder.ipp.
View newest version in sPHENIX GitHub at line 135 of file DoubleHitSpacePointBuilder.ipp
bool Acts::detail::calculateSpacePoint | ( | const std::pair< Vector3D, Vector3D > & | stripEnds1, |
const std::pair< Vector3D, Vector3D > & | stripEnds2, | ||
const Vector3D & | posVertex, | ||
SpacePointParameters & | spaPoPa, | ||
const double | stripLengthTolerance | ||
) |
This function performs a straight forward calculation of a space point and returns whether it was succesful or not.
[in] | stripEnds1 | Top and bottom end of the first strip detector element |
[in] | stripEnds1 | Top and bottom end of the second strip detector element |
[in] | posVertex | Position of the vertex |
[in,out] | spaPoPa | Data container of the calculations |
[in] | stripLengthTolerance | Tolerance scaling factor on the strip detector element length |
The following algorithm is meant for finding the position on the first strip if there is a corresponding cluster on the second strip. The resulting point is a point x on the first surfaces. This point is along a line between the points a (top end of the strip) and b (bottom end of the strip). The location can be parametrized as 2 * x = (1 + m) a + (1 - m) b as function of the scalar m. m is a parameter in the interval -1 < m < 1 since the hit was on the strip. Furthermore, the vector from the vertex to the cluster on the second strip y is needed to be a multiple k of the vector from vertex to the hit on the first strip x. As a consequence of this demand y = k * x needs to be on the connecting line between the top (c) and bottom (d) end of the second strip. If both clusters correspond to each other, the condition y * (c X d) = k * x (c X d) = 0 ("X" represents a cross product) needs to be fulfilled. Inserting the first equation into this equation leads to the condition for m as given in the following algorithm and therefore to the calculation of x. The same calculation can be repeated for y. Its corresponding parameter will be named n.
Definition at line 262 of file DoubleHitSpacePointBuilder.ipp.
View newest version in sPHENIX GitHub at line 262 of file DoubleHitSpacePointBuilder.ipp
References Acts::detail::SpacePointParameters::limit, Acts::detail::SpacePointParameters::m, Acts::detail::SpacePointParameters::n, Acts::detail::SpacePointParameters::q, Acts::detail::SpacePointParameters::qs, Acts::detail::SpacePointParameters::r, Acts::detail::SpacePointParameters::rt, Acts::detail::SpacePointParameters::s, and Acts::detail::SpacePointParameters::t.
void Acts::detail::covarianceTransport | ( | std::reference_wrapper< const GeometryContext > | geoContext, |
BoundSymMatrix & | covarianceMatrix, | ||
BoundMatrix & | jacobian, | ||
FreeMatrix & | transportJacobian, | ||
FreeVector & | derivatives, | ||
BoundToFreeMatrix & | jacobianLocalToGlobal, | ||
const FreeVector & | parameters, | ||
const Surface & | surface | ||
) |
Method for on-demand transport of the covariance to a new frame at current position in parameter space.
[in] | geoContext | The geometry context |
[in,out] | covarianceMatrix | The covariance matrix of the state |
[in,out] | jacobian | Full jacobian since the last reset |
[in,out] | transportJacobian | Global jacobian since the last reset |
[in,out] | derivatives | Path length derivatives of the free, nominal parameters |
[in,out] | jacobianLocalToGlobal | Projection jacobian of the last bound parametrisation to free parameters |
[in] | parameters | Free, nominal parametrisation |
[in] | surface | is the surface to which the covariance is forwarded to |
Referenced by Acts::Test::BOOST_AUTO_TEST_CASE(), boundState(), Acts::AtlasStepper< ConstantBField >::boundState(), Acts::StraightLineStepper::covarianceTransport(), Acts::EigenStepper< bfield_t, extensionlist_t, auctioneer_t >::covarianceTransport(), curvilinearState(), and Acts::AtlasStepper< ConstantBField >::curvilinearState().
void Acts::detail::covarianceTransport | ( | BoundSymMatrix & | covarianceMatrix, |
BoundMatrix & | jacobian, | ||
FreeMatrix & | transportJacobian, | ||
FreeVector & | derivatives, | ||
BoundToFreeMatrix & | jacobianLocalToGlobal, | ||
const Vector3D & | direction | ||
) |
Method for on-demand transport of the covariance to a new frame at current position in parameter space.
[in,out] | covarianceMatrix | The covariance matrix of the state |
[in,out] | jacobian | Full jacobian since the last reset |
[in,out] | transportJacobian | Global jacobian since the last reset |
[in,out] | derivatives | Path length derivatives of the free, nominal parameters |
[in,out] | jacobianLocalToGlobal | Projection jacobian of the last bound parametrisation to free parameters |
[in] | direction | Normalised direction vector |
void Acts::detail::covarianceTransport | ( | Covariance & | covarianceMatrix, |
Jacobian & | jacobian, | ||
FreeMatrix & | transportJacobian, | ||
FreeVector & | derivatives, | ||
BoundToFreeMatrix & | jacobianLocalToGlobal, | ||
const Vector3D & | direction | ||
) |
Definition at line 272 of file CovarianceEngine.cpp.
View newest version in sPHENIX GitHub at line 272 of file CovarianceEngine.cpp
void Acts::detail::covarianceTransport | ( | std::reference_wrapper< const GeometryContext > | geoContext, |
Covariance & | covarianceMatrix, | ||
Jacobian & | jacobian, | ||
FreeMatrix & | transportJacobian, | ||
FreeVector & | derivatives, | ||
BoundToFreeMatrix & | jacobianLocalToGlobal, | ||
const FreeVector & | parameters, | ||
const Surface & | surface | ||
) |
Definition at line 293 of file CovarianceEngine.cpp.
View newest version in sPHENIX GitHub at line 293 of file CovarianceEngine.cpp
std::tuple<CurvilinearParameters, BoundMatrix, double> Acts::detail::curvilinearState | ( | BoundSymMatrix & | covarianceMatrix, |
BoundMatrix & | jacobian, | ||
FreeMatrix & | transportJacobian, | ||
FreeVector & | derivatives, | ||
BoundToFreeMatrix & | jacobianLocalToGlobal, | ||
const FreeVector & | parameters, | ||
bool | covTransport, | ||
double | accumulatedPath | ||
) |
This creates a curvilinear state.
Create and return a curvilinear state at the current position
[in,out] | covarianceMatrix | The covariance matrix of the state |
[in,out] | jacobian | Full jacobian since the last reset |
[in,out] | transportJacobian | Global jacobian since the last reset |
[in,out] | derivatives | Path length derivatives of the free, nominal parameters |
[in,out] | jacobianLocalToGlobal | Projection jacobian of the last bound parametrisation to free parameters |
[in] | parameters | Free, nominal parametrisation |
[in] | covTransport | Decision whether the covariance transport should be performed |
[in] | accumulatedPath | Propagated distance |
Referenced by Acts::CombinatorialKalmanFilter< propagator_t, updater_t, smoother_t, source_link_selector_t, branch_stopper_t, calibrator_t, input_converter_t, output_converter_t >::Actor< source_link_t, parameters_t >::addPassiveState(), Acts::Test::BOOST_AUTO_TEST_CASE(), Acts::StraightLineStepper::curvilinearState(), Acts::EigenStepper< bfield_t, extensionlist_t, auctioneer_t >::curvilinearState(), and Acts::CombinatorialKalmanFilter< propagator_t, updater_t, smoother_t, source_link_selector_t, branch_stopper_t, calibrator_t, input_converter_t, output_converter_t >::Actor< source_link_t, parameters_t >::filter().
CurvilinearState Acts::detail::curvilinearState | ( | Covariance & | covarianceMatrix, |
Jacobian & | jacobian, | ||
FreeMatrix & | transportJacobian, | ||
FreeVector & | derivatives, | ||
BoundToFreeMatrix & | jacobianLocalToGlobal, | ||
const FreeVector & | parameters, | ||
bool | covTransport, | ||
double | accumulatedPath | ||
) |
Definition at line 244 of file CovarianceEngine.cpp.
View newest version in sPHENIX GitHub at line 244 of file CovarianceEngine.cpp
References kdfinder::abs(), charge, covarianceTransport(), Acts::eFreeDir0, Acts::eFreePos0, Acts::eFreeQOverP, Acts::eFreeTime, momentum, and Acts::VectorHelpers::time().
double Acts::detail::differenceOfClustersChecked | ( | const Vector3D & | pos1, |
const Vector3D & | pos2, | ||
const Vector3D & | posVertex, | ||
const double | maxDistance, | ||
const double | maxAngleTheta2, | ||
const double | maxAnglePhi2 | ||
) |
Calculates (Delta theta)^2 + (Delta phi)^2 between two clusters.
[in] | pos1 | position of the first cluster |
[in] | pos2 | position the second cluster |
[in] | maxDistance | Maximum distance between two clusters |
[in] | maxAngleTheta2 | Maximum squared theta angle between two clusters |
[in] | maxAnglePhi2 | Maximum squared phi angle between two clusters |
Definition at line 55 of file DoubleHitSpacePointBuilder.ipp.
View newest version in sPHENIX GitHub at line 55 of file DoubleHitSpacePointBuilder.ipp
References norm, Acts::VectorHelpers::phi(), and Acts::VectorHelpers::theta().
Calculates the equivalent angles phi and theta in the [-pi, pi) and [0, pi] ranges by ensuring the correct theta bounds
Definition at line 42 of file periodic.hpp.
View newest version in sPHENIX GitHub at line 42 of file periodic.hpp
References kdfinder::abs(), M_PI, radian_sym(), and T.
Referenced by FW::ParticleSmearing::execute(), Acts::FullBilloirVertexFitter< input_track_t, linearizer_t >::fit(), and Acts::KalmanVertexTrackUpdater::update().
std::pair<Vector2D, Vector2D> Acts::detail::findLocalTopAndBottomEnd | ( | const Vector2D & | local, |
const CartesianSegmentation * | segment | ||
) |
This function finds the top and bottom end of a detector segment in local coordinates.
[in] | local | Local position of the cluster |
[in] | segment | Segmentation of the detector element |
Definition at line 95 of file DoubleHitSpacePointBuilder.ipp.
View newest version in sPHENIX GitHub at line 95 of file DoubleHitSpacePointBuilder.ipp
References Acts::BinUtility::binningData(), Acts::CartesianSegmentation::binUtility(), Acts::binX, and Acts::binY.
Calculate the equivalent angle in the [0, 2*pi) range.
Definition at line 28 of file periodic.hpp.
View newest version in sPHENIX GitHub at line 28 of file periodic.hpp
Calculate the equivalent angle in the [-pi, pi) range.
Definition at line 34 of file periodic.hpp.
View newest version in sPHENIX GitHub at line 34 of file periodic.hpp
Referenced by Acts::RadialBounds::checkConsistency(), Acts::ConeBounds::checkConsistency(), Acts::EllipseBounds::checkConsistency(), Acts::CylinderBounds::checkConsistency(), Acts::DiscTrapezoidBounds::checkConsistency(), Acts::AnnulusBounds::checkConsistency(), Acts::CylinderVolumeBounds::checkConsistency(), Acts::EllipseBounds::distanceToBoundary(), ensureThetaBounds(), Acts::EllipseBounds::inside(), Acts::CylinderBounds::inside3D(), Acts::RadialBounds::shifted(), Acts::CylinderBounds::shifted(), and Acts::ConeBounds::shifted().
bool Acts::detail::recoverSpacePoint | ( | SpacePointParameters & | spaPoPa, |
double | stripLengthGapTolerance | ||
) |
This function tests if a space point can be estimated by a more tolerant treatment of construction. In fact, this function indirectly allows shifts of the vertex.
[in] | spaPoPa | container that stores geometric parameters and rules of the space point formation |
[in] | stripLengthGapTolerance | Tolerance scaling factor of the gap between strip detector elements |
Consider some cases that would allow an easy exit
The following code considers an overshoot of m and n in the same direction of their SDE. The term "overshoot" represents the amount of m or n outside its regular interval (-1, 1). It calculates which overshoot is worse. In order to compare both, the overshoot in n is projected onto the first surface by considering the normalized projection of r onto q. This allows a rescaling of the overshoot. The worse overshoot will be set to +/-1, the parameter with less overshoot will be moved towards 0 by the worse overshoot. In order to treat both SDEs equally, the rescaling eventually needs to be performed several times. If these shifts allows m and n to be in the limits, the space point can be stored.
Definition at line 170 of file DoubleHitSpacePointBuilder.ipp.
View newest version in sPHENIX GitHub at line 170 of file DoubleHitSpacePointBuilder.ipp
References Acts::detail::SpacePointParameters::limit, Acts::detail::SpacePointParameters::limitExtended, Acts::detail::SpacePointParameters::m, max, Acts::detail::SpacePointParameters::n, Acts::detail::SpacePointParameters::q, Acts::detail::SpacePointParameters::qmag, Acts::detail::SpacePointParameters::qs, Acts::detail::SpacePointParameters::r, and Acts::detail::SpacePointParameters::t.
|
inline |
Definition at line 299 of file Helpers.hpp.
View newest version in sPHENIX GitHub at line 299 of file Helpers.hpp
References kdfinder::abs().
Referenced by Acts::toString().
void Acts::detail::updateSingleStepSize | ( | typename stepper_t::State & | state, |
const object_intersection_t & | oIntersection, | ||
bool | release = true |
||
) |
Update the Step size - single component
It takes a (valid) object intersection from the compatibleX(...) calls in the geometry and updates the step size
state | [in,out] The stepping state (thread-local cache) |
oIntersection | [in] The object that yielded this step size |
release | [in] A release flag |
Definition at line 75 of file SteppingHelper.hpp.
View newest version in sPHENIX GitHub at line 75 of file SteppingHelper.hpp
References Acts::ConstrainedStep::actor.
Acts::Intersection::Status Acts::detail::updateSingleSurfaceStatus | ( | const stepper_t & | stepper, |
typename stepper_t::State & | state, | ||
const Surface & | surface, | ||
const BoundaryCheck & | bcheck | ||
) |
Update surface status - Single component
This method intersect the provided surface and update the navigation step estimation accordingly (hence it changes the state). It also returns the status of the intersection to trigger onSurface in case the surface is reached.
state | [in,out] The stepping state (thread-local cache) |
surface | [in] The surface provided |
bcheck | [in] The boundary check for this status update |
Definition at line 32 of file SteppingHelper.hpp.
View newest version in sPHENIX GitHub at line 32 of file SteppingHelper.hpp
References Acts::ConstrainedStep::aborter, Acts::ConstrainedStep::actor, and Acts::Surface::intersect().
Wrap a periodic value back into the nominal range.
Definition at line 17 of file periodic.hpp.
View newest version in sPHENIX GitHub at line 17 of file periodic.hpp
|
static |
Definition at line 40 of file GeometryStatics.hpp.
View newest version in sPHENIX GitHub at line 40 of file GeometryStatics.hpp
constexpr bool Acts::detail::action_signature_check_v |
Definition at line 80 of file action_signature_check.hpp.
View newest version in sPHENIX GitHub at line 80 of file action_signature_check.hpp
Referenced by Acts::ActionList< actors_t >::operator()().
constexpr bool Acts::detail::all_of_v = all_of<values...>::value |
Definition at line 30 of file all_of.hpp.
View newest version in sPHENIX GitHub at line 30 of file all_of.hpp
Referenced by Acts::Test::BOOST_AUTO_TEST_CASE(), Acts::ActionList< actors_t >::operator()(), and Acts::AbortList< PathLimitReached >::operator()().
constexpr bool Acts::detail::any_of_v = any_of<values...>::value |
Definition at line 30 of file any_of.hpp.
View newest version in sPHENIX GitHub at line 30 of file any_of.hpp
Referenced by Acts::Test::BOOST_AUTO_TEST_CASE().
constexpr bool Acts::detail::has_action_type_v |
Meta function which returns a compile time bool
T | the type to check |
Definition at line 99 of file type_collector.hpp.
View newest version in sPHENIX GitHub at line 99 of file type_collector.hpp
Referenced by Acts::Test::BOOST_AUTO_TEST_CASE().
constexpr bool Acts::detail::has_duplicates_v = has_duplicates<Args...>::value |
Definition at line 45 of file has_duplicates.hpp.
View newest version in sPHENIX GitHub at line 45 of file has_duplicates.hpp
Referenced by Acts::Test::BOOST_AUTO_TEST_CASE().
constexpr bool Acts::detail::has_result_type_v |
Meta function which returns a compile time bool
T | the type to check |
Definition at line 84 of file type_collector.hpp.
View newest version in sPHENIX GitHub at line 84 of file type_collector.hpp
Referenced by Acts::Test::BOOST_AUTO_TEST_CASE().
constexpr auto Acts::detail::type_collector |
The main type collector. This loops over the given tuple of actions or aborters, filters by predicate and uses extracter to construct a resulting output set.
Definition at line 55 of file type_collector.hpp.
View newest version in sPHENIX GitHub at line 55 of file type_collector.hpp
constexpr auto Acts::detail::type_collector_t |
Helper around type_collector which constructrs a hana tuple input from variadic template args, and pre-unpacks the predicate and extractor from the helper type
helper | Either result_type_extractor or action_type_extractor |
items | The items to filter / collect from. |
Definition at line 75 of file type_collector.hpp.
View newest version in sPHENIX GitHub at line 75 of file type_collector.hpp
Referenced by Acts::Test::BOOST_AUTO_TEST_CASE().