32 if (std::find(clique->conditional()->beginParents(),
33 clique->conditional()->endParents(),
key)
34 != clique->conditional()->endParents()) {
37 for(
Key i: clique->conditional()->frontals()) {
38 additionalKeys.insert(
i);
70 const bool debug =
ISDEBUG(
"IncrementalFixedLagSmoother update");
73 std::cout <<
"IncrementalFixedLagSmoother::update() Start" << std::endl;
75 std::cout <<
"END" << std::endl;
79 boost::optional<FastMap<Key, int> > constrainedKeys = boost::none;
88 std::cout <<
"Current Timestamp: " << current_timestamp << std::endl;
95 std::cout <<
"Marginalizable Keys: ";
96 for(
Key key: marginalizableKeys) {
99 std::cout << std::endl;
106 std::cout <<
"Constrained Keys: ";
107 if (constrainedKeys) {
109 iter != constrainedKeys->end(); ++
iter) {
114 std::cout << std::endl;
118 std::set<Key> additionalKeys;
119 for(
Key key: marginalizableKeys) {
125 KeyList additionalMarkedKeys(additionalKeys.begin(), additionalKeys.end());
129 factorsToRemove, constrainedKeys, boost::none, additionalMarkedKeys);
133 "Bayes Tree After Update, Before Marginalization:");
134 std::cout <<
"END" << std::endl;
138 if (marginalizableKeys.size() > 0) {
140 marginalizableKeys.end());
149 std::cout <<
"END" << std::endl;
160 std::cout <<
"IncrementalFixedLagSmoother::update() Finish" << std::endl;
169 while (iter != end) {
179 if (marginalizableKeys.size() > 0) {
184 constrainedKeys->operator[](timestamp_key.second) = 1;
187 for(
Key key: marginalizableKeys) {
188 constrainedKeys->operator[](
key) = 0;
195 const std::string& label) {
200 std::cout << std::endl;
207 for(
Key key: factor->keys()) {
210 std::cout <<
" )" << std::endl;
216 std::cout << label << std::endl;
224 const std::string& label) {
225 std::cout << label << std::endl;
226 if (!isam.
roots().empty()) {
231 std::cout <<
"{Empty Tree}" << std::endl;
239 std::cout << indent <<
"P( ";
240 for(
Key key: clique->conditional()->frontals()) {
243 if (clique->conditional()->nrParents() > 0)
245 for(
Key key: clique->conditional()->parents()) {
248 std::cout <<
")" << std::endl;
void updateKeyTimestampMap(const KeyTimestampMap &newTimestamps)
static void PrintSymbolicFactor(const GaussianFactor::shared_ptr &factor)
size_t iterations
The number of optimizer iterations performed.
std::map< Key, double > KeyTimestampMap
Typedef for a Key-Timestamp map/database.
bool equals(const FixedLagSmoother &rhs, double tol=1e-9) const override
size_t linearVariables
The number of variables that must keep a constant linearization point.
void eraseKeysBefore(double timestamp)
boost::shared_ptr< This > shared_ptr
double error
The final factor graph error.
virtual bool equals(const FixedLagSmoother &rhs, double tol=1e-9) const
KeyTimestampMap keyTimestampMap_
FastVector< FactorIndex > FactorIndices
Define collection types:
KeyVector findKeysBefore(double timestamp) const
iterator iter(handle obj)
const mpreal root(const mpreal &x, unsigned long int k, mp_rnd_t r=mpreal::get_default_rnd())
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
void createOrderingConstraints(const KeyVector &marginalizableKeys, boost::optional< FastMap< Key, int > > &constrainedKeys) const
virtual void print(const std::string &s="FixedLagSmoother:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
void eraseKeyTimestampMap(const KeyVector &keys)
Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const KeyTimestampMap ×tamps=KeyTimestampMap(), const FactorIndices &factorsToRemove=FactorIndices()) override
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
const KeyTimestampMap & timestamps() const
virtual bool equals(const ISAM2 &other, double tol=1e-9) const
void marginalizeLeaves(const FastList< Key > &leafKeys, boost::optional< FactorIndices & > marginalFactorsIndices=boost::none, boost::optional< FactorIndices & > deletedFactorsIndices=boost::none)
void print(const std::string &s="IncrementalFixedLagSmoother:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
An iSAM2-based fixed-lag smoother.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
double getCurrentTimestamp() const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
NonlinearISAM isam(relinearizeInterval)
Base::sharedClique sharedClique
Shared pointer to a clique.
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
size_t nonlinearVariables
The number of variables that can be relinearized.
void recursiveMarkAffectedKeys(const Key &key, const ISAM2Clique::shared_ptr &clique, std::set< Key > &additionalKeys)
static void PrintSymbolicTreeHelper(const gtsam::ISAM2Clique::shared_ptr &clique, const std::string indent="")
TimestampKeyMap timestampKeyMap_
static void PrintSymbolicTree(const gtsam::ISAM2 &isam, const std::string &label="Bayes Tree:")
static void PrintKeySet(const std::set< Key > &keys, const std::string &label="Keys:")
static void PrintSymbolicGraph(const GaussianFactorGraph &graph, const std::string &label="Factor Graph:")
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const boost::optional< FastMap< Key, int > > &constrainedKeys=boost::none, const boost::optional< FastList< Key > > &noRelinKeys=boost::none, const boost::optional< FastList< Key > > &extraReelimKeys=boost::none, bool force_relinearize=false)
const Roots & roots() const
std::uint64_t Key
Integer nonlinear key type.