Skip to content

Commit c262864

Browse files
committed
Parameter tuning
1 parent 22c624e commit c262864

4 files changed

Lines changed: 35 additions & 27 deletions

File tree

AtReconstruction/AtFitter/OpenKF/kalman_filter/TrackFitterUKF.h

Lines changed: 20 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -70,17 +70,29 @@ class TrackFitterUKFBase {
7070
float32_t m_weightC0;
7171
/// Unscented transform weight for the other sigma points
7272
float32_t m_weighti;
73-
/// Kappa parameter for sigma point calculation
74-
float32_t m_kappa{3 - DIM_A};
73+
/// Lambda parameter for sigma point calculation
74+
float32_t m_lambda{0};
7575

7676
public:
77-
TrackFitterUKFBase() { updateWeights(); }
77+
TrackFitterUKFBase() { setParameters(1, 2, 0); }
7878
~TrackFitterUKFBase() = default;
7979

80-
void setKappa(float32_t kappa)
80+
/**
81+
* @brief Set the weights used to calculate sigma points.
82+
*/
83+
void setParameters(float alpha, float beta, float kappa)
8184
{
82-
m_kappa = kappa; // Set the kappa parameter for sigma point calculation
83-
updateWeights(); // Update the weights based on the new kappa value
85+
static_assert(DIM_A > 0, "DIM_A is Zero which leads to numerical issue.");
86+
87+
m_lambda = alpha * alpha * (DIM_A + kappa) - DIM_A;
88+
float32_t denoTerm = m_lambda + static_cast<float32_t>(DIM_A);
89+
90+
m_weightM0 = m_lambda / denoTerm;
91+
m_weightC0 = m_weightM0 + (1.0F - alpha * alpha + beta); // Weight for the mean sigma point in covariance
92+
m_weighti = 0.5F / denoTerm;
93+
LOG(info) << "Mean weight " << m_weightM0;
94+
LOG(info) << "Cov weight: " << m_weightC0;
95+
LOG(info) << "Shared weight: " << m_weighti;
8496
}
8597

8698
/**
@@ -200,24 +212,6 @@ class TrackFitterUKFBase {
200212
}
201213

202214
protected:
203-
/**
204-
* @brief Set the weights used to calculate sigma points.
205-
*/
206-
void updateWeights()
207-
{
208-
static_assert(DIM_A > 0, "DIM_A is Zero which leads to numerical issue.");
209-
210-
constexpr float alpha = 1.0; // Scaling parameter, set to 1 to match orig
211-
constexpr float beta = 2.0; // Optimal for Gaussian distributions
212-
213-
float lambda{alpha * alpha * (DIM_A + m_kappa) - DIM_A}; // Lambda parameter for sigma points
214-
// lambda = m_kappa
215-
const float32_t denoTerm{lambda + static_cast<float32_t>(DIM_A)};
216-
217-
m_weightM0 = lambda / denoTerm;
218-
m_weightC0 = m_weightM0 + (1.0F - alpha * alpha + beta); // Weight for the mean sigma point in covariance
219-
m_weighti = 0.5F / denoTerm;
220-
}
221215
/**
222216
* @brief Add state vector and state covariance matrix to the augmented state vector covariance matrix.
223217
*/
@@ -328,7 +322,7 @@ class TrackFitterUKFBase {
328322
Matrix<STATE_DIM, SIGMA_DIM>
329323
calculateSigmaPoints(const Vector<STATE_DIM> &vecXa, const Matrix<STATE_DIM, STATE_DIM> &matPa)
330324
{
331-
const float32_t scalarMultiplier{std::sqrt(STATE_DIM + m_kappa)}; // sqrt(n + \kappa)
325+
const float32_t scalarMultiplier{std::sqrt(STATE_DIM + m_lambda)}; // sqrt(n + \kappa)
332326

333327
Eigen::LLT<Matrix<STATE_DIM, STATE_DIM>> lltOfPa = calculateCholesky<STATE_DIM>(matPa);
334328

@@ -447,6 +441,7 @@ class TrackFitterUKF : public TrackFitterUKFBase<6, 3, 1, 3> {
447441
using EigenVectorDimX = std::vector<Vector<TF_DIM_X>, Eigen::aligned_allocator<Vector<TF_DIM_X>>>;
448442
using VectorEigenMatDimX =
449443
std::vector<Matrix<TF_DIM_X, TF_DIM_X>, Eigen::aligned_allocator<Matrix<TF_DIM_X, TF_DIM_X>>>;
444+
450445
// vectors to hold the information needed for smoothing the UKF
451446
EigenVectorDimX m_vecXPredHist; /// @brief History of predicted state vectors at k+1
452447
VectorEigenMatDimX m_matPPredHist; /// @brief History of predicted state covariances at k+1

AtReconstruction/AtFitter/OpenKF/kalman_filter/TrackFitterUKFTest.cxx

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -77,6 +77,7 @@ TEST_F(TrackFitterUKFExampleTest, Prediction)
7777

7878
m_ukf.setCovarianceQ(Q);
7979
m_ukf.setCovarianceR(R);
80+
m_ukf.setParameters(1, 0, 3 - m_ukf.DIM_A); // Set kappa to match the original implementation
8081

8182
m_ukf.predictUKF(funcF, z);
8283

@@ -138,6 +139,7 @@ TEST_F(TrackFitterUKFExampleTest, PredictionAndCorrection)
138139

139140
m_ukf.setCovarianceQ(Q);
140141
m_ukf.setCovarianceR(R);
142+
m_ukf.setParameters(1, 0, 3 - m_ukf.DIM_A); // Set kappa to match the original implementation
141143

142144
m_ukf.predictUKF(funcF, z);
143145

@@ -188,7 +190,7 @@ TEST_F(TrackFitterUKFExampleTest, PredictionAndCorrection)
188190
// [ 0.00651178 -0.0046378 0.13023154 -0.00210188]
189191
// [-0.00465059 0.01344241 -0.00210188 0.1333886 ]]
190192

191-
ASSERT_NEAR(m_ukf.vecX()[0], 2.47414017F, FLOAT_EPSILON);
193+
ASSERT_NEAR(m_ukf.vecX()[0], 2.4758845F, FLOAT_EPSILON);
192194
ASSERT_NEAR(m_ukf.vecX()[1], 0.53327217F, FLOAT_EPSILON);
193195
ASSERT_NEAR(m_ukf.vecX()[2], 0.21649734F, FLOAT_EPSILON);
194196
ASSERT_NEAR(m_ukf.vecX()[3], -0.21214576F, FLOAT_EPSILON);

macro/tests/UKF/AtPropagator.C

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,14 @@ void AtPropagator()
3333
auto elossModel = std::make_unique<AtTools::AtELossTable>(0);
3434
elossModel->LoadSrimTable(getEnergyPath()); // Use the function to get the path
3535
elossModel->SetDensity(3.553e-5); // Set density in g/cm^3 for 300 torr H2
36-
AtTools::AtPropagator propagator(charge, mass, std::move(elossModel));
36+
37+
auto elossModel2 = std::make_unique<AtTools::AtELossCATIMA>(3.553e-5);
38+
elossModel2->SetProjectile(1, 1, 1);
39+
std::vector<std::tuple<int, int, int>> mat;
40+
mat.push_back({1, 1, 1});
41+
elossModel2->SetMaterial(mat);
42+
43+
AtTools::AtPropagator propagator(charge, mass, std::move(elossModel2));
3744
propagator.SetEField({0, 0, 0}); // No electric field
3845
propagator.SetBField({0, 0, 2.85}); // Magnetic field
3946
AtTools::AtRK4Stepper stepper;

macro/tests/UKF/UKFSingleTrack.C

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -88,6 +88,7 @@ void UKFSingleTrack()
8888
startPos *= 10; // Convert to mm
8989
XYZVector startMom(0.00935463, -0.0454279, 0.00826042); // Start momentum in GeV/c
9090
startMom *= 1e3;
91+
double beginMom = startMom.R(); // Initial momentum in MeV/c
9192

9293
XYZPoint nextPos(x[1], y[1], z[1]);
9394
startMom = startMom.R() * (nextPos - startPos).Unit(); // Set momentum direction towards the first hit
@@ -98,6 +99,7 @@ void UKFSingleTrack()
9899
double sigma_theta = 1 * M_PI / 180; // Angular uncertainty of 1 degree
99100
double sigma_phi = 1 * M_PI / 180; // Angular uncertainty of 1 degree
100101
ukf.fEnableEnStraggling = true; // Enable energy straggling
102+
ukf.setParameters(1e-2, 2, 0); // Set kappa to match the original implementation
101103

102104
TMatrixD cov(6, 6);
103105
cov.Zero();
@@ -200,6 +202,8 @@ void UKFSingleTrack()
200202
eLossSmooth.push_back(0); // First point has no previous state to compare
201203
}
202204
}
205+
LOG(info) << "Initial smoothed momentum: " << smoothedStates[0][3];
206+
LOG(info) << "Starting momentum: " << beginMom;
203207

204208
TGraph2D *track = new TGraph2D(x.size(), x.data(), y.data(), z.data());
205209
track->SetTitle("Particle Track;X [mm];Y [mm];Z [mm]");

0 commit comments

Comments
 (0)