33 #define TEST_VERBOSE_OUTPUT 0 35 #if TEST_VERBOSE_OUTPUT 36 #define TEST_COUT(ARGS_) std::cout << ARGS_ 38 #define TEST_COUT(ARGS_) void(0) 42 static const double tol = 1
e-3;
47 const double fx = 200.0;
48 const double fy = 150.0;
49 const double cx = 512.0;
50 const double cy = 384.0;
64 static std::map<timestep_t, std::vector<stereo_meas_t>>
dataset = {
66 {{0, 911.99993896, 712.00000000, 384.0},
67 {159, 311.99996948, 211.99996948, 384.0},
68 {3, 378.66665649, 312.00000000, 384.0},
69 {2, 645.33331299, 578.66662598, 384.0},
70 {157, 111.99994659, 11.99993896, 384.0},
71 {4, 578.66662598, 545.33331299, 384.0},
72 {5, 445.33331299, 412.00000000, 384.0},
73 {6, 562.00000000, 537.00000000, 384.0}}},
75 {{0, 1022.06353760, 762.57519531, 384.0},
76 {159, 288.30487061, 177.80273438, 384.0},
77 {2, 655.30645752, 583.12127686, 384.0},
78 {3, 368.60937500, 297.43176270, 384.0},
79 {4, 581.82666016, 547.16766357, 384.0},
80 {5, 443.66183472, 409.23681641, 384.0},
81 {6, 564.35980225, 538.62115479, 384.0},
82 {7, 461.66418457, 436.05477905, 384.0},
83 {8, 550.32220459, 531.75256348, 384.0},
84 {9, 476.17767334, 457.67541504, 384.0}}},
86 {{159, 257.97128296, 134.26287842, 384.0},
87 {2, 666.87255859, 588.07275391, 384.0},
88 {3, 356.53823853, 280.10061646, 384.0},
89 {4, 585.10949707, 548.99212646, 384.0},
90 {5, 441.66403198, 406.05108643, 384.0},
91 {6, 566.75402832, 540.21868896, 384.0},
92 {7, 461.16207886, 434.90002441, 384.0},
93 {8, 552.28387451, 533.30230713, 384.0},
94 {9, 476.63549805, 457.79418945, 384.0},
95 {10, 546.48394775, 530.53009033, 384.0}}},
97 {{159, 218.10592651, 77.30914307, 384.0},
98 {2, 680.54644775, 593.68103027, 384.0},
99 {3, 341.92507935, 259.28231812, 384.0},
100 {4, 588.53289795, 550.80499268, 384.0},
101 {5, 439.29989624, 402.39105225, 384.0},
102 {6, 569.18627930, 541.78991699, 384.0},
103 {7, 460.47863770, 433.51678467, 384.0},
104 {8, 554.24902344, 534.82952881, 384.0},
105 {9, 477.00451660, 457.80438232, 384.0},
106 {10, 548.33770752, 532.07501221, 384.0},
107 {11, 483.58688354, 467.47830200, 384.0},
108 {12, 542.36785889, 529.29321289, 384.0}}},
110 {{2, 697.09454346, 600.18432617, 384.0},
111 {3, 324.03643799, 233.97094727, 384.0},
112 {4, 592.11877441, 552.60449219, 384.0},
113 {5, 436.52197266, 398.19531250, 384.0},
114 {6, 571.66101074, 543.33209229, 384.0},
115 {7, 459.59658813, 431.88333130, 384.0},
116 {8, 556.21801758, 536.33258057, 384.0},
117 {9, 477.27893066, 457.69882202, 384.0},
118 {10, 550.18920898, 533.60003662, 384.0},
119 {11, 484.24472046, 467.86862183, 384.0},
120 {12, 544.14727783, 530.86157227, 384.0},
121 {13, 491.26141357, 478.11267090, 384.0},
122 {14, 541.29949951, 529.57086182, 384.0},
123 {15, 494.58111572, 482.95935059, 384.0}}}};
144 {0, {0.000000, 0.000000, 0.0}},
145 {1, {0.042019, -0.008403, 0.0}},
146 {2, {0.084783, -0.016953, 0.0}},
147 {3, {0.128305, -0.025648, 0.0}},
148 {4, {0.172605, -0.034490, 0.0}}};
151 TEST(testISAM2SmartFactor, Stereo_Batch) {
152 TEST_COUT(
"============ Running: Batch ============\n");
154 using namespace gtsam;
162 auto priorPoseNoise = noiseModel::Diagonal::Sigmas(
163 (
Vector(6) << Vector3::Constant(0.2), Vector3::Constant(0.2)).finished());
166 std::map<lm_id_t, FactorIndex> lm2factor;
169 std::map<lm_id_t, SmartStereoProjectionPoseFactor::shared_ptr> smartFactors;
175 for (
const auto &entries :
dataset) {
178 const auto kf_id = entries.first;
179 const std::vector<stereo_meas_t> &obs = entries.second;
182 if (smartFactors.count(stObs.lm_id) == 0) {
183 auto noise = noiseModel::Isotropic::Sigma(3, 0.1);
186 smartFactors[stObs.lm_id] =
187 std::make_shared<SmartStereoProjectionPoseFactor>(noise, parm);
189 batch_graph.
push_back(smartFactors[stObs.lm_id]);
192 TEST_COUT(
"Adding stereo observation from KF #" << kf_id <<
" for LM #" 193 << stObs.lm_id <<
"\n");
195 smartFactors[stObs.lm_id]->add(
201 batch_graph.
addPrior(
X(kf_id), Pose3::Identity(), priorPoseNoise);
204 batch_values.
insert(
X(kf_id), Pose3::Identity());
208 #if TEST_VERBOSE_OUTPUT 209 parameters.
verbosity = NonlinearOptimizerParams::LINEAR;
210 parameters.
verbosityLM = LevenbergMarquardtParams::TRYDELTA;
216 #if TEST_VERBOSE_OUTPUT 217 finalEstimate.
print(
"LevMarq estimate:");
232 TEST(testISAM2SmartFactor, Stereo_iSAM2) {
233 TEST_COUT(
"======= Running: iSAM2 ==========\n");
235 #if TEST_VERBOSE_OUTPUT 240 using namespace gtsam;
248 parameters.relinearizeThreshold = 0.01;
249 parameters.evaluateNonlinearError =
true;
252 parameters.cacheLinearizedFactors =
false;
256 parameters.relinearizeSkip = 1;
261 auto priorPoseNoise = noiseModel::Diagonal::Sigmas(
262 (
Vector(6) << Vector3::Constant(0.2), Vector3::Constant(0.2)).finished());
265 std::map<lm_id_t, FactorIndex> lm2factor;
268 std::map<lm_id_t, SmartStereoProjectionPoseFactor::shared_ptr> smartFactors;
270 Pose3 lastKeyframePose = Pose3::Identity();
273 for (
const auto &entries :
dataset) {
276 const auto kf_id = entries.first;
277 const std::vector<stereo_meas_t> &obs = entries.second;
285 std::map<FactorIndex, lm_id_t> newFactor2lm;
288 if (smartFactors.count(stObs.lm_id) == 0) {
289 auto noise = noiseModel::Isotropic::Sigma(3, 0.1);
292 smartFactors[stObs.lm_id] =
293 std::make_shared<SmartStereoProjectionPoseFactor>(noise,
params);
294 newFactor2lm[newFactors.
size()] = stObs.lm_id;
295 newFactors.
push_back(smartFactors[stObs.lm_id]);
298 factorNewAffectedKeys[lm2factor.at(stObs.lm_id)].insert(
X(kf_id));
301 TEST_COUT(
"Adding stereo observation from KF #" << kf_id <<
" for LM #" 302 << stObs.lm_id <<
"\n");
304 smartFactors[stObs.lm_id]->add(
310 newFactors.
addPrior(
X(kf_id), Pose3::Identity(), priorPoseNoise);
316 newValues.
insert(
X(kf_id), lastKeyframePose);
318 TEST_COUT(
"Running iSAM2 for frame: " << kf_id <<
"\n");
325 for (
const auto &f2l : newFactor2lm)
333 TEST_COUT(
"error before2: " << res2.errorBefore.value() <<
"\n");
334 TEST_COUT(
"error after2 : " << res2.errorAfter.value() <<
"\n");
337 #if TEST_VERBOSE_OUTPUT 338 currentEstimate.
print(
"currentEstimate:");
343 lastKeyframePose = currentEstimate.at(
X(kf_id)).cast<
Pose3>();
virtual const Values & optimize()
static int runAllTests(TestResult &result)
const ValueType at(Key j) const
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const std::optional< FastMap< Key, int > > &constrainedKeys={}, const std::optional< FastList< Key > > &noRelinKeys={}, const std::optional< FastList< Key > > &extraReelimKeys={}, bool force_relinearize=false)
Smart stereo factor on poses, assuming camera calibration is fixed.
static const SmartProjectionParams params
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
FactorIndices newFactorsIndices
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
static std::map< timestep_t, std::vector< stereo_meas_t > > dataset
std::optional< FastMap< FactorIndex, KeySet > > newAffectedKeys
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
#define EXPECT(condition)
stereo_meas_t(lm_id_t id, double lu, double ru, double v_lr)
static const std::map< timestep_t, gtsam::Point3 > gt_positions
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::optional< double > errorBefore
NonlinearISAM isam(relinearizeInterval)
cout<< "Here is the matrix m:"<< endl<< m<< endl;Eigen::FullPivLU< Matrix5x3 > lu(m)
static ConjugateGradientParameters parameters
TEST(testISAM2SmartFactor, Stereo_Batch)
std::optional< double > errorAfter
void insert(Key j, const Value &val)
VerbosityLM verbosityLM
The verbosity level for Levenberg-Marquardt (default: SILENT), see also NonlinearOptimizerParams::ver...
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Values calculateEstimate() const