Analysis Software
Documentation for sPHENIX simulation software
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Acts::VectorHelpers Namespace Reference

Namespaces

namespace  detail
 

Functions

template<typename Derived >
double phi (const Eigen::MatrixBase< Derived > &v) noexcept
 
template<typename T , std::enable_if_t< detail::has_phi_method< T >::value, int > = 0>
double phi (const T &v) noexcept
 
template<typename Derived >
double perp (const Eigen::MatrixBase< Derived > &v) noexcept
 
template<typename Derived >
double theta (const Eigen::MatrixBase< Derived > &v) noexcept
 
template<typename Derived >
double eta (const Eigen::MatrixBase< Derived > &v) noexcept
 
std::array< ActsScalar, 5 > evaluateTrigonomics (const Vector3 &direction)
 Fast evaluation of trigonomic functions.
 
double cast (const Vector3 &position, BinningValue bval)
 
ActsMatrix< 3, 3 > cross (const ActsMatrix< 3, 3 > &m, const Vector3 &v)
 Calculates column-wise cross products of a matrix and a vector and stores the result column-wise in a matrix.
 
auto position (const Vector4 &pos4)
 Access the three-position components in a four-position vector.
 
auto position (const FreeVector &params)
 Access the three-position components in a free parameters vector.
 
template<typename vector3_t >
auto makeVector4 (const Eigen::MatrixBase< vector3_t > &vec3, typename vector3_t::Scalar w) -> Eigen::Matrix< typename vector3_t::Scalar, 4, 1 >
 Construct a four-vector from a three-vector and scalar fourth component.
 
std::pair< double, doubleincidentAngles (const Acts::Vector3 &direction, const Acts::RotationMatrix3 &globalToLocal)
 

Function Documentation

double Acts::VectorHelpers::cast ( const Vector3 &  position,
BinningValue  bval 
)
inline

Helper method to extract the binning value from a 3D vector.

For this method a 3D vector is required to guarantee all potential binning values.

Definition at line 153 of file VectorHelpers.hpp.

View newest version in sPHENIX GitHub at line 153 of file VectorHelpers.hpp

References assert, Acts::binEta, Acts::binH, Acts::binMag, Acts::binPhi, Acts::binR, Acts::binRPhi, Acts::binX, Acts::binY, Acts::binZ, eta(), perp(), phi(), and theta().

Referenced by Acts::GeometryObject::binningPositionValue(), Acts::Extent::extend(), Acts::Experimental::MultiLayerSurfacesUpdatorImpl< grid_t, path_generator >::fillCasts(), Acts::Experimental::KdtSurfaces< kDIM, bSize, reference_generator >::fillCasts(), Acts::Experimental::IndexedUpdatorImpl< VariableBoundIndexGrid1, DetectorVolumesCollection, DetectorVolumeFiller >::fillCasts(), Acts::TGeoParser::select(), and Acts::PortalJsonConverter::toJsonDetray().

+ Here is the call graph for this function:

+ Here is the caller graph for this function:

ActsMatrix<3, 3> Acts::VectorHelpers::cross ( const ActsMatrix< 3, 3 > &  m,
const Vector3 &  v 
)
inline
template<typename Derived >
double Acts::VectorHelpers::eta ( const Eigen::MatrixBase< Derived > &  v)
noexcept

Calculate the pseudorapidity for a vector.

Template Parameters
DerivedEigen derived concrete type
Parameters
vAny vector like Eigen type, static or dynamic
Note
Will static assert that the number of rows of v is at least 3, or in case of dynamic size, will abort execution if that is not the case.
Returns
The pseudorapidity value

Definition at line 113 of file VectorHelpers.hpp.

View newest version in sPHENIX GitHub at line 113 of file VectorHelpers.hpp

References assert, autodiff::detail::copysign(), perp(), parse_cmake_options::rows, and testSigmaEff::v.

Referenced by Acts::Test::BOOST_AUTO_TEST_CASE(), cast(), Acts::dbscanTrackClustering(), ActsExamples::ParticleSelector::execute(), ActsExamples::TruthSeedSelector::execute(), ActsExamples::TrackSummaryPlotTool::fill(), ActsExamples::ResPlotTool::fill(), Acts::AmbiguityTrackClassifier::inferScores(), Fatras::casts::eta::operator()(), Fatras::casts::absEta::operator()(), Acts::ObjectSorterT< Vector3 >::operator()(), Acts::DistanceSorterT< T >::operator()(), Acts::BinningData::value(), ActsEvaluator::visitTrackStates(), ActsExamples::RootParticleWriter::writeT(), ActsExamples::CsvMultiTrajectoryWriter::writeT(), and ActsExamples::RootTrajectoryStatesWriter::writeT().

+ Here is the call graph for this function:

+ Here is the caller graph for this function:

std::array<ActsScalar, 5> Acts::VectorHelpers::evaluateTrigonomics ( const Vector3 &  direction)
inline

Fast evaluation of trigonomic functions.

Parameters
directionfor this evaluatoin
Returns
cos(phi), sin(phi), cos(theta), sin(theta), 1/sin(theta)

Definition at line 135 of file VectorHelpers.hpp.

View newest version in sPHENIX GitHub at line 135 of file VectorHelpers.hpp

References ambiguity_solver_full_chain::x, y, and physmon_track_finding_ttbar::z.

Referenced by Acts::detail::anglesToDirectionJacobian(), Acts::Surface::boundToFreeJacobian(), Acts::detail::curvilinearToFreeJacobian(), Acts::detail::directionToAnglesJacobian(), Acts::Surface::freeToBoundJacobian(), and Acts::detail::freeToCurvilinearJacobian().

+ Here is the caller graph for this function:

std::pair<double, double> Acts::VectorHelpers::incidentAngles ( const Acts::Vector3 direction,
const Acts::RotationMatrix3 globalToLocal 
)
inline

Calculate the incident angles of a vector with in a given reference frame

Template Parameters
DerivedEigen derived concrete type
Parameters
directionThe crossing direction in the global frame
globalToLocalRotation from global to local frame
Returns
The angles of incidence in the two normal planes

Definition at line 224 of file VectorHelpers.hpp.

View newest version in sPHENIX GitHub at line 224 of file VectorHelpers.hpp

References phi(), and theta().

Referenced by Acts::Test::BOOST_AUTO_TEST_CASE(), and ActsExamples::RootMeasurementWriter::writeT().

+ Here is the call graph for this function:

+ Here is the caller graph for this function:

template<typename vector3_t >
auto Acts::VectorHelpers::makeVector4 ( const Eigen::MatrixBase< vector3_t > &  vec3,
typename vector3_t::Scalar  w 
) -> Eigen::Matrix<typename vector3_t::Scalar, 4, 1>
inline

Construct a four-vector from a three-vector and scalar fourth component.

Definition at line 206 of file VectorHelpers.hpp.

View newest version in sPHENIX GitHub at line 206 of file VectorHelpers.hpp

References Acts::ePos0, Acts::ePos1, Acts::ePos2, and Acts::eTime.

Referenced by Acts::Test::BOOST_AUTO_TEST_CASE(), Acts::Test::BOOST_DATA_TEST_CASE(), Acts::SurfaceMaterialMapper::mapInteraction(), Acts::VolumeMaterialMapper::mapMaterialTrack(), and Acts::EventDataView3DTest::testMultiTrajectory().

+ Here is the caller graph for this function:

template<typename Derived >
double Acts::VectorHelpers::perp ( const Eigen::MatrixBase< Derived > &  v)
noexcept

Calculate radius in the transverse (xy) plane of a vector

Template Parameters
DerivedEigen derived concrete type
Parameters
vAny vector like Eigen type, static or dynamic
Note
Will static assert that the number of rows of v is at least 2, or in case of dynamic size, will abort execution if that is not the case.
Returns
The transverse radius value.

Definition at line 72 of file VectorHelpers.hpp.

View newest version in sPHENIX GitHub at line 72 of file VectorHelpers.hpp

References assert, parse_cmake_options::rows, and testSigmaEff::v.

Referenced by ActsFatras::PlanarSurfaceMask::apply(), Acts::Test::BOOST_AUTO_TEST_CASE(), ActsFatras::BOOST_AUTO_TEST_CASE(), Acts::Test::BOOST_DATA_TEST_CASE(), Acts::Test::BOOST_FIXTURE_TEST_CASE(), cast(), Acts::LayerCreator::checkBinning(), FastJetAlgoSub::cluster_and_fill(), PHG4InnerHcalDetector::ConstructScintillatorBox(), PHG4OuterHcalDetector::ConstructScintillatorBox(), PHG4InnerHcalDetector::ConstructSteelPlate(), PHG4OuterHcalDetector::ConstructSteelPlate(), Acts::Svg::SurfaceArrayConverter::convert(), Acts::detail::PointwiseMaterialInteraction::covarianceContributions(), genfit::MeasurementCreator::create(), Acts::SurfaceArrayCreator::createVariableAxis(), Acts::DD4hepLayerBuilder::endcapLayers(), Fatras::Test::Particle::energyLoss(), eta(), ActsExamples::ParticleSelector::execute(), ActsExamples::TruthSeedSelector::execute(), Acts::fieldMapRZ(), ActsExamples::TrackSummaryPlotTool::fill(), ActsExamples::DuplicationPlotTool::fill(), ActsExamples::FakeRatePlotTool::fill(), ActsExamples::ResPlotTool::fill(), Acts::SolenoidBField::getField(), Acts::ConeSurface::globalToLocal(), Acts::CylinderSurface::globalToLocal(), Acts::LineSurface::globalToLocal(), Acts::globalToLocalFromBin(), Acts::CutoutCylinderVolumeBounds::inside(), Acts::ConeVolumeBounds::inside(), Acts::CylinderVolumeBounds::inside(), Acts::CylinderBounds::inside3D(), Acts::SurfaceArrayCreator::isSurfaceEquivalent(), Acts::ConeSurface::localCartesianToBoundLocalDerivative(), Acts::CylinderSurface::localCartesianToBoundLocalDerivative(), main(), Acts::materialMapperRZ(), Acts::ObjectSorterT< Vector3 >::operator()(), Fatras::casts::pT::operator()(), ActsFatras::PlanarSurfaceTestBeds::operator()(), ActsFatras::Casts::Pt::operator()(), Fatras::casts::vR::operator()(), Acts::Test::PerpendicularMeasure::operator()(), Acts::DistanceSorterT< T >::operator()(), Acts::Test::SurfaceObserver< Surface >::operator()(), PHHepMCParticleSelectorDecayProductChain::process_event(), MyJetAnalysis::process_event(), sPHAnalysis::process_event_pythiaupsilon(), PseudoJet::pseudorapidity(), ActsExamples::RootBFieldWriter::run(), ActsExamples::CsvBFieldWriter::run(), Fatras::Test::Particle::scatter(), ActsFatras::Channelizer::segments(), Acts::solenoidFieldMap(), Acts::SurfaceArrayCreator::surfaceArrayOnDisc(), theta(), Acts::CylinderVolumeBuilder::trackingVolume(), Fatras::Test::Particle::update(), Acts::BinningData::value(), ActsExamples::RootParticleWriter::writeT(), ActsExamples::CsvMultiTrajectoryWriter::writeT(), ActsExamples::CKFPerformanceWriter::writeT(), ActsExamples::RootTrajectorySummaryWriter::writeT(), and ActsExamples::RootTrajectoryStatesWriter::writeT().

template<typename Derived >
double Acts::VectorHelpers::phi ( const Eigen::MatrixBase< Derived > &  v)
noexcept

Calculate phi (transverse plane angle) from compatible Eigen types

Template Parameters
DerivedEigen derived concrete type
Parameters
vAny vector like Eigen type, static or dynamic
Note
Will static assert that the number of rows of v is at least 2, or in case of dynamic size, will abort execution if that is not the case.
Returns
The value of the angle in the transverse plane.

Definition at line 40 of file VectorHelpers.hpp.

View newest version in sPHENIX GitHub at line 40 of file VectorHelpers.hpp

References assert, parse_cmake_options::rows, and testSigmaEff::v.

Referenced by ActsFatras::PlanarSurfaceMask::annulusMask(), ActsFatras::PlanarSurfaceMask::apply(), Acts::Test::BOOST_AUTO_TEST_CASE(), ActsFatras::BOOST_AUTO_TEST_CASE(), ActsExamples::MockupSectorBuilder::buildSector(), cast(), ActsFatras::NuclearInteraction::convertParametersToParticles(), Acts::dbscanTrackClustering(), Acts::SpacePointUtility::differenceOfMeasurementsChecked(), Acts::EventDataView3D::drawCovarianceAngular(), Acts::estimateTrackParamsFromSeed(), ActsExamples::ParticleSmearing::execute(), ActsExamples::ParticleSelector::execute(), ActsExamples::TruthSeedSelector::execute(), ActsExamples::ResPlotTool::fill(), ActsExamples::RootMeasurementWriter::DigitizationTree::fillTruthParameters(), Acts::Frustum< value_t, DIM, SIDES >::Frustum(), Acts::globalToLocalFromBin(), incidentAngles(), Acts::AmbiguityTrackClassifier::inferScores(), Acts::EllipseBounds::inside(), Acts::CutoutCylinderVolumeBounds::inside(), Acts::ConeVolumeBounds::inside(), Acts::CylinderVolumeBounds::inside(), Acts::detail::IntersectionHelper2D::intersectCircleSegment(), Acts::ConeSurface::localCartesianToBoundLocalDerivative(), Acts::CylinderSurface::localCartesianToBoundLocalDerivative(), Acts::LineSurface::localCartesianToBoundLocalDerivative(), main(), Acts::ObjectSorterT< Vector3 >::operator()(), Fatras::Scattering< formula_t >::operator()(), Acts::Test::MeasurementsCreator::operator()(), Acts::DistanceSorterT< T >::operator()(), Acts::Experimental::PathGridSurfacesGenerator::operator()(), Acts::ConeSurface::pathCorrection(), Acts::MultiComponentBoundTrackParameters::phi(), ActsFatras::Particle::phi(), ActsFatras::Channelizer::segments(), Acts::AnnulusBounds::stripXYToModulePC(), Acts::Test::CylindricalTrackingGeometry::surfacesCylinder(), Acts::BinningData::value(), Acts::AnnulusBounds::vertices(), ActsExamples::RootParticleWriter::writeT(), and ActsExamples::CsvMultiTrajectoryWriter::writeT().

+ Here is the caller graph for this function:

template<typename T , std::enable_if_t< detail::has_phi_method< T >::value, int > = 0>
double Acts::VectorHelpers::phi ( const T v)
noexcept

Calculate phi (transverse plane angle) from anything implementing a method like phi() returning anything convertible to double.

Template Parameters
Tanything that has a phi method
Parameters
vAny type that implements a phi method
Returns
The phi value

Definition at line 61 of file VectorHelpers.hpp.

View newest version in sPHENIX GitHub at line 61 of file VectorHelpers.hpp

References testSigmaEff::v.

auto Acts::VectorHelpers::position ( const Vector4 &  pos4)
inline

Access the three-position components in a four-position vector.

Definition at line 195 of file VectorHelpers.hpp.

View newest version in sPHENIX GitHub at line 195 of file VectorHelpers.hpp

References Acts::ePos0.

Referenced by Acts::Test::BOOST_AUTO_TEST_CASE(), and Acts::Vertex< input_track_t >::position().

+ Here is the caller graph for this function:

auto Acts::VectorHelpers::position ( const FreeVector &  params)
inline

Access the three-position components in a free parameters vector.

Definition at line 200 of file VectorHelpers.hpp.

View newest version in sPHENIX GitHub at line 200 of file VectorHelpers.hpp

References Acts::eFreePos0.

template<typename Derived >
double Acts::VectorHelpers::theta ( const Eigen::MatrixBase< Derived > &  v)
noexcept

Calculate the theta angle (longitudinal w.r.t. z axis) of a vector

Template Parameters
DerivedEigen derived concrete type
Parameters
vAny vector like Eigen type, static or dynamic
Note
Will static assert that the number of rows of v is at least 3, or in case of dynamic size, will abort execution if that is not the case.
Returns
The theta value

Definition at line 93 of file VectorHelpers.hpp.

View newest version in sPHENIX GitHub at line 93 of file VectorHelpers.hpp

References assert, perp(), parse_cmake_options::rows, and testSigmaEff::v.

Referenced by Acts::Test::BOOST_AUTO_TEST_CASE(), cast(), ActsFatras::NuclearInteraction::convertParametersToParticles(), Acts::SpacePointUtility::differenceOfMeasurementsChecked(), Acts::EventDataView3D::drawCovarianceAngular(), Acts::estimateTrackParamsFromSeed(), ActsExamples::ParticleSmearing::execute(), ActsExamples::ResPlotTool::fill(), ActsExamples::RootMeasurementWriter::DigitizationTree::fillTruthParameters(), incidentAngles(), main(), Fatras::Scattering< formula_t >::operator()(), Acts::Test::MeasurementsCreator::operator()(), Acts::MultiComponentBoundTrackParameters::theta(), ActsFatras::Particle::theta(), and ActsFatras::PlanarSurfaceDrift::toReadout().

+ Here is the call graph for this function:

+ Here is the caller graph for this function: