gtsam/cpp/Pose2Graph.cpp

35 lines
997 B
C++
Raw Normal View History

2009-12-11 07:45:38 +08:00
/**
* @file Pose2Graph.cpp
* @brief A factor graph for the 2D PoseSLAM problem
* @authors Frank Dellaert, Viorela Ila
*/
2010-01-14 06:25:03 +08:00
#include "Pose2Graph.h"
2009-12-11 07:45:38 +08:00
#include "FactorGraph-inl.h"
#include "NonlinearFactorGraph-inl.h"
2010-01-14 09:44:00 +08:00
#include "NonlinearOptimizer-inl.h"
#include "NonlinearEquality.h"
#include "graph-inl.h"
2009-12-11 07:45:38 +08:00
using namespace std;
using namespace gtsam;
2009-12-11 07:45:38 +08:00
namespace gtsam {
2010-01-14 09:44:00 +08:00
// explicit instantiation so all the code is there and we can link with it
template class FactorGraph<NonlinearFactor<Pose2Config> > ;
template class NonlinearFactorGraph<Pose2Config> ;
template class NonlinearEquality<Pose2Config,Pose2Config::Key,Pose2> ;
template class NonlinearOptimizer<Pose2Graph, Pose2Config>;
2009-12-11 07:45:38 +08:00
2010-01-14 09:44:00 +08:00
void Pose2Graph::addConstraint(const Pose2Config::Key& key, const Pose2& pose) {
push_back(sharedFactor(new NonlinearEquality<Pose2Config, Pose2Config::Key,
Pose2> (key, pose)));
}
2010-01-14 09:44:00 +08:00
bool Pose2Graph::equals(const Pose2Graph& p, double tol) const {
return false;
}
2009-12-11 07:45:38 +08:00
} // namespace gtsam