testDecisionTreeFactor.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
12 /*
13  * testDecisionTreeFactor.cpp
14  *
15  * @date Feb 5, 2012
16  * @author Frank Dellaert
17  * @author Duy-Nguyen Ta
18  */
19 
21 #include <gtsam/base/Testable.h>
27 #include <gtsam/inference/Key.h>
29 
30 using namespace std;
31 using namespace gtsam;
32 
34 DecisionTreeFactor create(const Signature& signature) {
35  DecisionTreeFactor p(signature.discreteKeys(), signature.cpt());
36  return p;
37 }
38 
39 /* ************************************************************************* */
40 TEST(DecisionTreeFactor, ConstructorsMatch) {
41  // Declare two keys
42  DiscreteKey X(0, 2), Y(1, 3);
43 
44  // Create with vector and with string
45  const std::vector<double> table{2, 5, 3, 6, 4, 7};
47  DecisionTreeFactor f2({X, Y}, "2 5 3 6 4 7");
49 }
50 
51 /* ************************************************************************* */
52 TEST(DecisionTreeFactor, constructors) {
53  // Declare a bunch of keys
54  DiscreteKey X(0, 2), Y(1, 3), Z(2, 2);
55 
56  // Create factors
57  DecisionTreeFactor f1(X, {2, 8});
58  DecisionTreeFactor f2(X & Y, "2 5 3 6 4 7");
59  DecisionTreeFactor f3(X & Y & Z, "2 5 3 6 4 7 25 55 35 65 45 75");
60  EXPECT_LONGS_EQUAL(1, f1.size());
61  EXPECT_LONGS_EQUAL(2, f2.size());
62  EXPECT_LONGS_EQUAL(3, f3.size());
63 
64  DiscreteValues x121{{0, 1}, {1, 2}, {2, 1}};
65  EXPECT_DOUBLES_EQUAL(8, f1(x121), 1e-9);
66  EXPECT_DOUBLES_EQUAL(7, f2(x121), 1e-9);
67  EXPECT_DOUBLES_EQUAL(75, f3(x121), 1e-9);
68 
69  // Assert that error = -log(value)
70  EXPECT_DOUBLES_EQUAL(-log(f1(x121)), f1.error(x121), 1e-9);
71 
72  // Construct from DiscreteConditional
73  DiscreteConditional conditional(X | Y = "1/1 2/3 1/4");
74  DecisionTreeFactor f4(conditional);
75  EXPECT_DOUBLES_EQUAL(0.8, f4(x121), 1e-9);
76 }
77 
78 /* ************************************************************************* */
80  // Declare a bunch of keys
81  DiscreteKey X(0, 2), Y(1, 3), Z(2, 2);
82 
83  // Create factors
84  DecisionTreeFactor f(X & Y & Z, "2 5 3 6 4 7 25 55 35 65 45 75");
85 
86  auto errors = f.errorTree();
87  // regression
89  {X, Y, Z},
90  vector<double>{-0.69314718, -1.6094379, -1.0986123, -1.7917595,
91  -1.3862944, -1.9459101, -3.2188758, -4.0073332, -3.5553481,
92  -4.1743873, -3.8066625, -4.3174881});
93  EXPECT(assert_equal(expected, errors, 1e-6));
94 }
95 
96 /* ************************************************************************* */
97 TEST(DecisionTreeFactor, multiplication) {
98  DiscreteKey v0(0, 2), v1(1, 2), v2(2, 2);
99 
100  // Multiply with a DiscreteDistribution, i.e., Bayes Law!
101  DiscreteDistribution prior(v1 % "1/3");
102  DecisionTreeFactor f1(v0 & v1, "1 2 3 4");
103  DecisionTreeFactor expected(v0 & v1, "0.25 1.5 0.75 3");
106 
107  // Multiply two factors
108  DecisionTreeFactor f2(v1 & v2, "5 6 7 8");
109  DecisionTreeFactor actual = f1 * f2;
110  DecisionTreeFactor expected2(v0 & v1 & v2, "5 6 14 16 15 18 28 32");
111  CHECK(assert_equal(expected2, actual));
112 }
113 
114 /* ************************************************************************* */
116  DiscreteKey A(0, 2), S(1, 2);
117  DecisionTreeFactor pA = create(A % "99/1"), pS = create(S % "50/50");
118  DecisionTreeFactor joint = pA * pS;
119 
120  DecisionTreeFactor s = joint / pA;
121 
122  // Factors are not equal due to difference in keys
124 
125  // The underlying data should be the same
127  EXPECT(assert_equal(ADT(pS), ADT(s)));
128 
129  KeySet keys(joint.keys());
130  keys.insert(pA.keys().begin(), pA.keys().end());
131  EXPECT(assert_inequal(KeySet(pS.keys()), keys));
132 
133 }
134 
135 /* ************************************************************************* */
137  DiscreteKey v0(0, 3), v1(1, 2);
138  DecisionTreeFactor f1(v0 & v1, "1 2 3 4 5 6");
139 
140  DecisionTreeFactor expected(v1, "9 12");
141  auto actual = std::dynamic_pointer_cast<DecisionTreeFactor>(f1.sum(1));
142  CHECK(actual);
143  CHECK(assert_equal(expected, *actual, 1e-5));
144 
145  DecisionTreeFactor expected2(v1, "5 6");
146  auto actual2 = std::dynamic_pointer_cast<DecisionTreeFactor>(f1.max(1));
147  CHECK(actual2);
148  CHECK(assert_equal(expected2, *actual2));
149 
150  DecisionTreeFactor f2(v1 & v0, "1 2 3 4 5 6");
151  auto actual22 = std::dynamic_pointer_cast<DecisionTreeFactor>(f2.sum(1));
152  CHECK(actual22);
153 }
154 
155 /* ************************************************************************* */
156 // Check enumerate yields the correct list of assignment/value pairs.
158  DiscreteKey A(12, 3), B(5, 2);
159  DecisionTreeFactor f(A & B, "1 2 3 4 5 6");
160  auto actual = f.enumerate();
161  std::vector<std::pair<DiscreteValues, double>> expected;
163  for (size_t a : {0, 1, 2}) {
164  for (size_t b : {0, 1}) {
165  values[12] = a;
166  values[5] = b;
167  expected.emplace_back(values, f(values));
168  }
169  }
170  EXPECT(actual == expected);
171 }
172 
173 namespace pruning_fixture {
174 
175 DiscreteKey A(1, 2), B(2, 2), C(3, 2);
176 DecisionTreeFactor f(A& B& C, "1 5 3 7 2 6 4 8");
177 
178 DiscreteKey D(4, 2);
180  D& C & B & A,
181  "0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 "
182  "0.0 0.0 0.99995287 1.0 1.0 1.0 1.0");
183 
184 } // namespace pruning_fixture
185 
186 /* ************************************************************************* */
187 // Check if computing the correct threshold works.
188 TEST(DecisionTreeFactor, ComputeThreshold) {
189  using namespace pruning_fixture;
190 
191  // Only keep the leaves with the top 5 values.
192  double threshold = f.computeThreshold(5);
193  EXPECT_DOUBLES_EQUAL(4.0, threshold, 1e-9);
194 
195  // Check for more extreme pruning where we only keep the top 2 leaves
196  threshold = f.computeThreshold(2);
197  EXPECT_DOUBLES_EQUAL(7.0, threshold, 1e-9);
198 
199  threshold = factor.computeThreshold(5);
200  EXPECT_DOUBLES_EQUAL(0.99995287, threshold, 1e-9);
201 
202  threshold = factor.computeThreshold(3);
203  EXPECT_DOUBLES_EQUAL(1.0, threshold, 1e-9);
204 
205  threshold = factor.computeThreshold(6);
206  EXPECT_DOUBLES_EQUAL(0.61247742, threshold, 1e-9);
207 }
208 
209 /* ************************************************************************* */
210 // Check pruning of the decision tree works as expected.
212  using namespace pruning_fixture;
213 
214  // Only keep the leaves with the top 5 values.
215  size_t maxNrAssignments = 5;
216  auto pruned5 = f.prune(maxNrAssignments);
217 
218  // Pruned leaves should be 0
219  DecisionTreeFactor expected(A & B & C, "0 5 0 7 0 6 4 8");
220  EXPECT(assert_equal(expected, pruned5));
221 
222  // Check for more extreme pruning where we only keep the top 2 leaves
223  maxNrAssignments = 2;
224  auto pruned2 = f.prune(maxNrAssignments);
225  DecisionTreeFactor expected2(A & B & C, "0 0 0 7 0 0 0 8");
226  EXPECT(assert_equal(expected2, pruned2));
227 
228  DecisionTreeFactor expected3(D & C & B & A,
229  "0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 "
230  "0.999952870000 1.0 1.0 1.0 1.0");
231  maxNrAssignments = 5;
232  auto pruned3 = factor.prune(maxNrAssignments);
233  EXPECT(assert_equal(expected3, pruned3));
234 }
235 
236 /* ************************************************************************** */
237 // Asia Bayes Network
238 /* ************************************************************************** */
239 
240 #define DISABLE_DOT
241 
242 void maybeSaveDotFile(const DecisionTreeFactor& f, const string& filename) {
243 #ifndef DISABLE_DOT
244  std::vector<std::string> names = {"A", "S", "T", "L", "B", "E", "X", "D"};
245  auto formatter = [&](Key key) { return names[key]; };
246  f.dot(filename, formatter, true);
247 #endif
248 }
249 
250 /* ************************************************************************* */
251 // test Asia Joint
253  DiscreteKey A(0, 2), S(1, 2), T(2, 2), L(3, 2), B(4, 2), E(5, 2), X(6, 2),
254  D(7, 2);
255 
256  gttic_(asiaCPTs);
257  DecisionTreeFactor pA = create(A % "99/1");
258  DecisionTreeFactor pS = create(S % "50/50");
259  DecisionTreeFactor pT = create(T | A = "99/1 95/5");
260  DecisionTreeFactor pL = create(L | S = "99/1 90/10");
261  DecisionTreeFactor pB = create(B | S = "70/30 40/60");
262  DecisionTreeFactor pE = create((E | T, L) = "F T T T");
263  DecisionTreeFactor pX = create(X | E = "95/5 2/98");
264  DecisionTreeFactor pD = create((D | E, B) = "9/1 2/8 3/7 1/9");
265 
266  // Create joint
267  gttic_(asiaJoint);
268  DecisionTreeFactor joint = pA;
269  maybeSaveDotFile(joint, "Asia-A");
270  joint = joint * pS;
271  maybeSaveDotFile(joint, "Asia-AS");
272  joint = joint * pT;
273  maybeSaveDotFile(joint, "Asia-AST");
274  joint = joint * pL;
275  maybeSaveDotFile(joint, "Asia-ASTL");
276  joint = joint * pB;
277  maybeSaveDotFile(joint, "Asia-ASTLB");
278  joint = joint * pE;
279  maybeSaveDotFile(joint, "Asia-ASTLBE");
280  joint = joint * pX;
281  maybeSaveDotFile(joint, "Asia-ASTLBEX");
282  joint = joint * pD;
283  maybeSaveDotFile(joint, "Asia-ASTLBEXD");
284 
285  // Check that discrete keys are as expected
286  EXPECT(assert_equal(joint.discreteKeys(), {A, S, T, L, B, E, X, D}));
287 
288  // Check that summing out variables maintains the keys even if merged, as is
289  // the case with S.
290  auto noAB = joint.sum(Ordering{A.first, B.first});
291  EXPECT(assert_equal(noAB->discreteKeys(), {S, T, L, E, X, D}));
292 }
293 
294 /* ************************************************************************* */
295 TEST(DecisionTreeFactor, DotWithNames) {
296  DiscreteKey A(12, 3), B(5, 2);
297  DecisionTreeFactor f(A & B, "1 2 3 4 5 6");
298  auto formatter = [](Key key) { return key == 12 ? "A" : "B"; };
299 
300  for (bool showZero : {true, false}) {
301  string actual = f.dot(formatter, showZero);
302  // pretty weak test, as ids are pointers and not stable across platforms.
303  string expected = "digraph G {";
304  EXPECT(actual.substr(0, 11) == expected);
305  }
306 }
307 
308 /* ************************************************************************* */
309 // Check markdown representation looks as expected.
311  DiscreteKey A(12, 3), B(5, 2);
312  DecisionTreeFactor f(A & B, "1 2 3 4 5 6");
313  string expected =
314  "|A|B|value|\n"
315  "|:-:|:-:|:-:|\n"
316  "|0|0|1|\n"
317  "|0|1|2|\n"
318  "|1|0|3|\n"
319  "|1|1|4|\n"
320  "|2|0|5|\n"
321  "|2|1|6|\n";
322  auto formatter = [](Key key) { return key == 12 ? "A" : "B"; };
323  string actual = f.markdown(formatter);
324  EXPECT(actual == expected);
325 }
326 
327 /* ************************************************************************* */
328 // Check markdown representation with a value formatter.
329 TEST(DecisionTreeFactor, markdownWithValueFormatter) {
330  DiscreteKey A(12, 3), B(5, 2);
331  DecisionTreeFactor f(A & B, "1 2 3 4 5 6");
332  string expected =
333  "|A|B|value|\n"
334  "|:-:|:-:|:-:|\n"
335  "|Zero|-|1|\n"
336  "|Zero|+|2|\n"
337  "|One|-|3|\n"
338  "|One|+|4|\n"
339  "|Two|-|5|\n"
340  "|Two|+|6|\n";
341  auto keyFormatter = [](Key key) { return key == 12 ? "A" : "B"; };
342  DecisionTreeFactor::Names names{{12, {"Zero", "One", "Two"}},
343  {5, {"-", "+"}}};
344  string actual = f.markdown(keyFormatter, names);
345  EXPECT(actual == expected);
346 }
347 
348 /* ************************************************************************* */
349 // Check html representation with a value formatter.
350 TEST(DecisionTreeFactor, htmlWithValueFormatter) {
351  DiscreteKey A(12, 3), B(5, 2);
352  DecisionTreeFactor f(A & B, "1 2 3 4 5 6");
353  string expected =
354  "<div>\n"
355  "<table class='DecisionTreeFactor'>\n"
356  " <thead>\n"
357  " <tr><th>A</th><th>B</th><th>value</th></tr>\n"
358  " </thead>\n"
359  " <tbody>\n"
360  " <tr><th>Zero</th><th>-</th><td>1</td></tr>\n"
361  " <tr><th>Zero</th><th>+</th><td>2</td></tr>\n"
362  " <tr><th>One</th><th>-</th><td>3</td></tr>\n"
363  " <tr><th>One</th><th>+</th><td>4</td></tr>\n"
364  " <tr><th>Two</th><th>-</th><td>5</td></tr>\n"
365  " <tr><th>Two</th><th>+</th><td>6</td></tr>\n"
366  " </tbody>\n"
367  "</table>\n"
368  "</div>";
369  auto keyFormatter = [](Key key) { return key == 12 ? "A" : "B"; };
370  DecisionTreeFactor::Names names{{12, {"Zero", "One", "Two"}},
371  {5, {"-", "+"}}};
372  string actual = f.html(keyFormatter, names);
373  EXPECT(actual == expected);
374 }
375 
376 /* ************************************************************************* */
377 int main() {
378  TestResult tr;
379  return TestRegistry::runAllTests(tr);
380 }
381 /* ************************************************************************* */
gtsam::Signature::cpt
std::vector< double > cpt() const
Definition: Signature.cpp:69
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::DiscreteFactor::errorTree
virtual AlgebraicDecisionTree< Key > errorTree() const
Compute error for each assignment and return as a tree.
Definition: DiscreteFactor.cpp:59
gtsam::markdown
string markdown(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of markdown.
Definition: DiscreteValues.cpp:130
gtsam::DecisionTreeFactor
Definition: DecisionTreeFactor.h:45
B
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Definition: bench_gemm.cpp:49
test_constructor::f1
auto f1
Definition: testHybridNonlinearFactor.cpp:56
gtsam::DecisionTreeFactor::computeThreshold
double computeThreshold(const size_t N) const
Compute the probability value which is the threshold above which only N leaves are present.
Definition: DecisionTreeFactor.cpp:454
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
v0
static const double v0
Definition: testCal3DFisheye.cpp:31
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
Testable.h
Concept check for values that can be used in unit tests.
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
gtsam::DecisionTreeFactor::dot
void dot(std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter, bool showZero=true) const
Definition: DecisionTreeFactor.cpp:299
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
b
Scalar * b
Definition: benchVecAdd.cpp:17
asiaCPTs::pX
ADT pX
Definition: testAlgebraicDecisionTree.cpp:159
gtsam::DiscreteDistribution
Definition: DiscreteDistribution.h:33
gtsam::Y
GaussianFactorGraphValuePair Y
Definition: HybridGaussianProductFactor.cpp:29
pruning_fixture::f
DecisionTreeFactor f(A &B &C, "1 5 3 7 2 6 4 8")
asiaCPTs::pA
ADT pA
Definition: testAlgebraicDecisionTree.cpp:153
pruning_fixture::C
DiscreteKey C(3, 2)
gtsam::DecisionTreeFactor::prune
DecisionTreeFactor prune(size_t maxNrAssignments) const
Prune the decision tree of discrete variables.
Definition: DecisionTreeFactor.cpp:508
asiaCPTs
Definition: testAlgebraicDecisionTree.cpp:149
maybeSaveDotFile
void maybeSaveDotFile(const DecisionTreeFactor &f, const string &filename)
Definition: testDecisionTreeFactor.cpp:242
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
f2
double f2(const Vector2 &x)
Definition: testNumericalDerivative.cpp:58
pruning_fixture::D
DiscreteKey D(4, 2)
T
Eigen::Triplet< double > T
Definition: Tutorial_sparse_example.cpp:6
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
log
const EIGEN_DEVICE_FUNC LogReturnType log() const
Definition: ArrayCwiseUnaryOps.h:128
Ordering.h
Variable ordering for the elimination algorithm.
X
#define X
Definition: icosphere.cpp:20
TEST
TEST(DecisionTreeFactor, ConstructorsMatch)
Definition: testDecisionTreeFactor.cpp:40
gtsam::FastSet< Key >
create
DecisionTreeFactor create(const Signature &signature)
Definition: testDecisionTreeFactor.cpp:34
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
gtsam::AlgebraicDecisionTree< Key >
pruning_fixture::factor
DecisionTreeFactor factor(D &C &B &A, "0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 " "0.0 0.0 0.99995287 1.0 1.0 1.0 1.0")
Key.h
asiaCPTs::pE
ADT pE
Definition: testAlgebraicDecisionTree.cpp:158
gtsam::KeySet
FastSet< Key > KeySet
Definition: Key.h:96
ADT
AlgebraicDecisionTree< Key > ADT
Definition: testAlgebraicDecisionTree.cpp:32
table
ArrayXXf table(10, 4)
main
int main()
Definition: testDecisionTreeFactor.cpp:377
gttic_
#define gttic_(label)
Definition: timing.h:245
relicense.filename
filename
Definition: relicense.py:57
DiscreteFactor.h
Signature.h
signatures for conditional densities
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
L
MatrixXd L
Definition: LLT_example.cpp:6
asiaCPTs::pT
ADT pT
Definition: testAlgebraicDecisionTree.cpp:155
asiaCPTs::pS
ADT pS
Definition: testAlgebraicDecisionTree.cpp:154
Eigen::Triplet< double >
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
asiaCPTs::pD
ADT pD
Definition: testAlgebraicDecisionTree.cpp:160
serializationTestHelpers.h
TestResult
Definition: TestResult.h:26
key
const gtsam::Symbol key('X', 0)
E
DiscreteKey E(5, 2)
process_shonan_timing_results.names
dictionary names
Definition: process_shonan_timing_results.py:175
gtsam::DiscreteConditional
Definition: DiscreteConditional.h:37
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam
traits
Definition: SFMdata.h:40
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
f3
double f3(double x1, double x2)
Definition: testNumericalDerivative.cpp:78
DiscreteDistribution.h
gtsam::Factor::keys
const KeyVector & keys() const
Access the factor's involved variable keys.
Definition: Factor.h:143
CHECK
#define CHECK(condition)
Definition: Test.h:108
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
std
Definition: BFloat16.h:88
p
float * p
Definition: Tutorial_Map_using.cpp:9
v2
Vector v2
Definition: testSerializationBase.cpp:39
gtsam::DecisionTreeFactor::html
std::string html(const KeyFormatter &keyFormatter=DefaultKeyFormatter, const Names &names={}) const override
Render as html table.
Definition: DecisionTreeFactor.cpp:351
gtsam::DecisionTreeFactor::sum
DiscreteFactor::shared_ptr sum(size_t nrFrontals) const override
Create new factor by summing all values with the same separator values.
Definition: DecisionTreeFactor.h:195
pruning_fixture
Definition: testDecisionTreeFactor.cpp:173
f4
double f4(double x, double y, double z)
Definition: testNumericalDerivative.cpp:107
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
gtsam::DecisionTreeFactor::enumerate
std::vector< std::pair< DiscreteValues, double > > enumerate() const
Enumerate all values into a map from values to double.
Definition: DecisionTreeFactor.cpp:231
gtsam::Signature::discreteKeys
DiscreteKeys discreteKeys() const
Definition: Signature.cpp:55
gtsam::assert_inequal
bool assert_inequal(const Matrix &A, const Matrix &B, double tol)
Definition: Matrix.cpp:61
different_sigmas::prior
const auto prior
Definition: testHybridBayesNet.cpp:238
gtsam::DiscreteFactor::discreteKeys
DiscreteKeys discreteKeys() const
Return all the discrete keys associated with this factor.
Definition: DiscreteFactor.cpp:37
asiaCPTs::pB
ADT pB
Definition: testAlgebraicDecisionTree.cpp:157
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
Z
#define Z
Definition: icosphere.cpp:21
gtsam::Ordering
Definition: inference/Ordering.h:33
asiaCPTs::pL
ADT pL
Definition: testAlgebraicDecisionTree.cpp:156
DecisionTreeFactor.h
gtsam::DecisionTreeFactor::markdown
std::string markdown(const KeyFormatter &keyFormatter=DefaultKeyFormatter, const Names &names={}) const override
Render as markdown table.
Definition: DecisionTreeFactor.cpp:320
gtsam::Signature
Definition: Signature.h:54
S
DiscreteKey S(1, 2)
v1
Vector v1
Definition: testSerializationBase.cpp:38


gtsam
Author(s):
autogenerated on Tue Jan 7 2025 04:07:09