41 using namespace gtsam;
 
   62                              const std::string indent = 
"") {
 
   64   std::cout << indent << 
"P( ";
 
   65   for (
Key key : clique->conditional()->frontals()) {
 
   68   if (clique->conditional()->nrParents() > 0) std::cout << 
"| ";
 
   69   for (
Key key : clique->conditional()->parents()) {
 
   72   std::cout << 
")" << std::endl;
 
   82   std::cout << label << std::endl;
 
   83   if (!
isam.roots().empty()) {
 
   88     std::cout << 
"{Empty Tree}" << std::endl;
 
   97   SETDEBUG(
"IncrementalFixedLagSmoother update", 
true);
 
  104   typedef IncrementalFixedLagSmoother::KeyTimestampMap Timestamps;
 
  120     Timestamps newTimestamps;
 
  124     newTimestamps[key0] = 0.0;
 
  127     fullinit.
insert(newValues);
 
  130     smoother.
update(newFactors, newValues, newTimestamps);
 
  145     Timestamps newTimestamps;
 
  150     newTimestamps[
key2] = double(
i);
 
  153     fullinit.
insert(newValues);
 
  156     smoother.
update(newFactors, newValues, newTimestamps);
 
  173     Timestamps newTimestamps;
 
  180     newTimestamps[
key2] = double(
i);
 
  183     fullinit.
insert(newValues);
 
  186     smoother.
update(newFactors, newValues, newTimestamps);
 
  201     Timestamps newTimestamps;
 
  210     newTimestamps[
key2] = double(
i);
 
  213     fullinit.
insert(newValues);
 
  216     smoother.
update(newFactors, newValues, newTimestamps);
 
  231     Timestamps newTimestamps;
 
  239     newTimestamps[
key2] = double(
i);
 
  243     fullinit.
insert(newValues);
 
  246     smoother.
update(newFactors, newValues, newTimestamps);
 
  256     Timestamps emptyNewTimestamps;
 
  261     factorToRemove.push_back(factorIndex);
 
  266     std::cout << 
"fullgraph.size() = " << fullgraph.
size() << std::endl;
 
  267     std::cout << 
"smootherFactorsBeforeRemove.size() = " 
  268               << smootherFactorsBeforeRemove.
size() << std::endl;
 
  271     smoother.
update(emptyNewFactors, emptyNewValues, emptyNewTimestamps,
 
  282     for (
size_t i = 0; 
i < smootherFactorsBeforeRemove.
size(); 
i++) {
 
  284       if (smootherFactorsBeforeRemove[
i] && 
i != factorIndex) {
 
  294     SETDEBUG(
"BayesTreeMarginalizationHelper", 
true);
 
  296                       "Bayes Tree Before marginalization test:");
 
  299     const int max_i = 500;
 
  302       Key key_1 = 
X(
i - 1);
 
  303       Key key_2 = 
X(
i - 2);
 
  304       Key key_3 = 
X(
i - 3);
 
  305       Key key_4 = 
X(
i - 4);
 
  306       Key key_5 = 
X(
i - 5);
 
  307       Key key_6 = 
X(
i - 6);
 
  308       Key key_7 = 
X(
i - 7);
 
  309       Key key_8 = 
X(
i - 8);
 
  310       Key key_9 = 
X(
i - 9);
 
  311       Key key_10 = 
X(
i - 10);
 
  315       Timestamps newTimestamps;
 
  340       newTimestamps[key_0] = double(
i);
 
  343       fullinit.
insert(newValues);
 
  346       smoother.
update(newFactors, newValues, newTimestamps);
 
  352           "Bayes Tree marginalization test: i = " + std::to_string(
i));