Skip to content

Commit

Permalink
refactor: remove dead code, default switch-cases (#2623)
Browse files Browse the repository at this point in the history
  • Loading branch information
AJPfleger authored Nov 17, 2023
1 parent af8a537 commit 86e63f3
Show file tree
Hide file tree
Showing 17 changed files with 33 additions and 53 deletions.
8 changes: 5 additions & 3 deletions Core/include/Acts/TrackFitting/detail/GsfUtils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ class ScopedGsfInfoPrinterAndChecker {
};

ActsScalar calculateDeterminant(
const double *fullCalibrated, const double *fullCalibratedCovariance,
const double *fullCalibratedCovariance,
TrackStateTraits<MultiTrajectoryTraits::MeasurementSizeMax,
true>::Covariance predictedCovariance,
TrackStateTraits<MultiTrajectoryTraits::MeasurementSizeMax, true>::Projector
Expand Down Expand Up @@ -186,8 +186,6 @@ void computePosteriorWeights(
// This abuses an incorrectly sized vector / matrix to access the
// data pointer! This works (don't use the matrix as is!), but be
// careful!
state.template calibrated<MultiTrajectoryTraits::MeasurementSizeMax>()
.data(),
state
.template calibratedCovariance<
MultiTrajectoryTraits::MeasurementSizeMax>()
Expand Down Expand Up @@ -233,6 +231,10 @@ struct MultiTrajectoryProjector {
case StatesType::eSmoothed:
return std::make_tuple(weights.at(idx), proxy.smoothed(),
proxy.smoothedCovariance());
default:
throw std::invalid_argument(
"Incorrect StatesType, should be ePredicted"
", eFiltered, or eSmoothed.");
}
}
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,5 @@ bool voidReverseFilteringLogic(

inline const Surface* voidSurfaceAccessor(const SourceLink& /*sourceLink*/) {
throw std::runtime_error{"voidSurfaceAccessor should not ever execute"};
return nullptr;
}
} // namespace Acts::detail
2 changes: 0 additions & 2 deletions Core/include/Acts/Utilities/BinAdjustment.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,8 +266,6 @@ BinUtility adjustBinUtility(const BinUtility& bu, const Surface& surface,

throw std::invalid_argument(
"Bin adjustment not implemented for this surface yet!");

return BinUtility();
}

} // namespace Acts
2 changes: 0 additions & 2 deletions Core/include/Acts/Utilities/BinAdjustmentVolume.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -215,8 +215,6 @@ BinUtility adjustBinUtility(const BinUtility& bu, const Volume& volume) {

throw std::invalid_argument(
"Bin adjustment not implemented for this volume yet!");

return BinUtility();
}

} // namespace Acts
6 changes: 2 additions & 4 deletions Core/src/Detector/detail/SupportHelper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -175,15 +175,13 @@ void Acts::Experimental::detail::SupportHelper::addSupport(
ActsScalar layerR = doff < 0 ? minR + doff : maxR + doff;
minZ -= std::abs(demin);
maxZ += std::abs(demax);
ActsScalar midZ = 0.5 * (minZ + maxZ);
ActsScalar halfZ = 0.5 * (maxZ - minZ);
// midZ / halfZ are overwritten if the cylinder
// is chosen to be concentric
// halfZ is overwritten if the cylinder is chosen to be concentric
Transform3 sTransform = Transform3::Identity();
if (concentric) {
midZ = 0.;
halfZ = std::max(std::abs(minZ), std::abs(maxZ));
} else {
ActsScalar midZ = 0.5 * (minZ + maxZ);
sTransform.pretranslate(Vector3(0., 0., midZ));
}
auto cSupport = SupportHelper::cylindricalSupport(
Expand Down
2 changes: 0 additions & 2 deletions Core/src/Geometry/KDTreeTrackingGeometryBuilder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,8 +143,6 @@ Acts::KDTreeTrackingGeometryBuilder::translateVolume(
return tVolume;
}
}

return nullptr;
}

/// @return a new tracking volume
Expand Down
14 changes: 7 additions & 7 deletions Core/src/Material/MaterialGridHelper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,13 +118,13 @@ std::function<double(Acts::Vector3)> Acts::globalToLocalFromBin(
};
break;

case Acts::binRPhi:
case Acts::binEta:
case Acts::binH:
case Acts::binMag:
case Acts::binValues:
throw std::invalid_argument("Incorrect bin, should be x,y,z,r,phi,z");
break;
// case Acts::binRPhi:
// case Acts::binEta:
// case Acts::binH:
// case Acts::binMag:
// case Acts::binValues:
default:
throw std::invalid_argument("Incorrect bin, should be x,y,z,r,phi");
}
return transfoGlobalToLocal;
}
Expand Down
5 changes: 1 addition & 4 deletions Core/src/TrackFitting/GsfUtils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,15 +19,12 @@ using TrackStateTraits =
TrackStateTraits<MultiTrajectoryTraits::MeasurementSizeMax, true>;

ActsScalar calculateDeterminant(
const double* fullCalibrated, const double* fullCalibratedCovariance,
const double* fullCalibratedCovariance,
TrackStateTraits::Covariance predictedCovariance,
TrackStateTraits::Projector projector, unsigned int calibratedSize) {
return visit_measurement(calibratedSize, [&](auto N) {
constexpr std::size_t kMeasurementSize = decltype(N)::value;

typename Acts::TrackStateTraits<kMeasurementSize, true>::Measurement
calibrated{fullCalibrated};

typename Acts::TrackStateTraits<
kMeasurementSize, true>::MeasurementCovariance calibratedCovariance{
fullCalibratedCovariance};
Expand Down
8 changes: 4 additions & 4 deletions Examples/Algorithms/Digitization/src/MeasurementCreation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,9 @@ ActsExamples::Measurement ActsExamples::createMeasurement(
return Acts::Measurement<Acts::BoundIndices, 4>(std::move(sl), indices,
par, cov);
};
default:
std::string errorMsg = "Invalid/mismatching measurement dimension: " +
std::to_string(dParams.indices.size());
throw std::runtime_error(errorMsg.c_str());
}
std::string errorMsg = "Invalid/mismatching measurement dimension: " +
std::to_string(dParams.indices.size());

throw std::runtime_error(errorMsg.c_str());
}
Original file line number Diff line number Diff line change
Expand Up @@ -52,14 +52,11 @@ std::vector<std::vector<Acts::Vector3>> modulePositionsDisc(
const std::vector<double>& moduleHalfLength) {
// calculate the radii
std::vector<double> radii;
// calculate the radial borders
std::vector<double> radialBoarders;
// the radial span of the disc
double deltaR = outerRadius - innerRadius;
// quick exits
if (discBinning.size() == 1) {
radii.push_back(0.5 * (innerRadius + outerRadius));
radialBoarders = {innerRadius, outerRadius};
} else {
double totalLength = 0;
// sum up the total length
Expand All @@ -72,17 +69,13 @@ std::vector<std::vector<Acts::Vector3>> modulePositionsDisc(
double lastR = innerRadius;
double lastHl = 0.;
double lastOl = 0.;
// remember the radial boarders
radialBoarders.push_back(innerRadius);
// now calculate
for (auto& mhlength : moduleHalfLength) {
// calculate the radius
radii.push_back(lastR + lastHl - lastOl + mhlength);
lastR = radii[radii.size() - 1];
lastOl = rOverlap;
lastHl = mhlength;
// and register the radial boarder
radialBoarders.push_back(lastR + 2 * lastHl - 0.5 * lastOl);
}
}
// now prepare the return method
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,6 @@ ActsExamples::MockupSectorBuilder::buildChamber(
const ActsExamples::MockupSectorBuilder::ChamberConfig& chamberConfig) {
if (g4World == nullptr) {
throw std::invalid_argument("MockupSector: No g4World initialized");
return nullptr;
}

const Acts::GeometryContext gctx;
Expand Down Expand Up @@ -162,7 +161,6 @@ ActsExamples::MockupSectorBuilder::buildSector(
detVolumes) {
if (mCfg.NumberOfSectors > maxNumberOfSectors) {
throw std::invalid_argument("MockupSector:Number of max sectors exceeded");
return nullptr;
}

const Acts::GeometryContext gctx;
Expand Down
1 change: 0 additions & 1 deletion Fatras/src/EventData/ProcessType.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@ std::ostream &operator<<(std::ostream &os, ProcessType processType) {
default:
return (os << static_cast<uint32_t>(processType));
}
return os;
}

} // namespace ActsFatras
2 changes: 2 additions & 0 deletions Plugins/Geant4/src/Geant4Converters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,6 +171,8 @@ Acts::Geant4ShapeConverter::rectangleBounds(const G4Box& g4Box) {
case 2: {
rAxes = {0, 1};
} break;
default: // do nothing
break;
}
auto rBounds = std::make_shared<RectangleBounds>(hG4XYZ[std::abs(rAxes[0u])],
hG4XYZ[std::abs(rAxes[1u])]);
Expand Down
2 changes: 2 additions & 0 deletions Tests/Benchmarks/AnnulusBoundsBenchmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,8 @@ int main(int /*argc*/, char** /*argv[]*/) {
case Mode::SlowOutside:
num_inside_points = NTESTS;
num_outside_points = NTESTS_SLOW;
default: // do nothing
break;
};

for (const auto& [loc, inside, label] : testPoints) {
Expand Down
2 changes: 2 additions & 0 deletions Tests/Benchmarks/BoundaryCheckBenchmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,8 @@ int main(int /*argc*/, char** /*argv[]*/) {
case Mode::SlowOutside:
num_inside_points = NTESTS;
num_outside_points = NTESTS_SLOW;
default: // do nothing
break;
};
run_bench([&] { return check.isInside(center, poly); }, num_inside_points,
"Center");
Expand Down
7 changes: 0 additions & 7 deletions Tests/UnitTests/Core/Propagator/JacobianEngineTests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,13 +55,6 @@ BOOST_AUTO_TEST_CASE(jacobian_engine_helper) {
direction = Vector3(1., 1., 999.).normalized();
f2cJacobian = detail::freeToCurvilinearJacobian(direction);

phi = VectorHelpers::phi(direction);
theta = VectorHelpers::theta(direction);
sinPhi = std::sin(phi);
cosPhi = std::cos(phi);
sinTheta = std::sin(theta);
cosTheta = std::cos(theta);

const ActsScalar c = std::hypot(direction.y(), direction.z());
const ActsScalar invC = 1. / c;
CHECK_CLOSE_REL(f2cJacobian(eBoundLoc0, eFreePos1), -direction.z() * invC,
Expand Down
15 changes: 8 additions & 7 deletions Tests/UnitTests/Core/Seeding/SeedFinderTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,23 +50,24 @@ std::vector<const SpacePoint*> readFile(const std::string& filename) {
std::stringstream ss(line);
std::string linetype;
ss >> linetype;
float x = 0, y = 0, z = 0, r = 0, varianceR = 0, varianceZ = 0;
if (linetype == "lxyz") {
float x = 0, y = 0, z = 0, varianceR = 0, varianceZ = 0;
ss >> layer >> x >> y >> z >> varianceR >> varianceZ;
r = std::hypot(x, y);
float f22 = varianceR;
float wid = varianceZ;
float cov = wid * wid * .08333;
if (cov < f22) {
cov = f22;
const float r = std::hypot(x, y);

float cov = varianceZ * varianceZ * .08333;
if (cov < varianceR) {
cov = varianceR;
}

if (std::abs(z) > 450.) {
varianceZ = 9. * cov;
varianceR = .06;
} else {
varianceR = 9. * cov;
varianceZ = .06;
}

SpacePoint* sp =
new SpacePoint{x, y, z, r, layer, varianceR, varianceZ};
// if(r < 200.){
Expand Down

0 comments on commit 86e63f3

Please sign in to comment.