27 #include <boost/archive/binary_oarchive.hpp> 28 #include <boost/archive/binary_iarchive.hpp> 29 #include <boost/serialization/export.hpp> 30 #include <boost/range/adaptor/reversed.hpp> 33 using namespace gtsam;
63 for(
const boost::shared_ptr<gtsam::NonlinearFactor>& nlf: graph) {
64 graph_dim += nlf->dim();
66 double dof = graph_dim - config.
dim();
67 return 2. * graph.error(config) / dof;
70 int main(
int argc,
char *argv[]) {
72 cout <<
"Loading data..." << endl;
77 std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr>
data =
84 cout <<
"Playing forward time steps..." << endl;
88 size_t nextMeasurement = 0;
89 for(
size_t step=1; nextMeasurement < measurements.
size(); ++
step) {
95 gttic_(Collect_measurements);
100 newFactors.
addPrior(0,
Pose(), noiseModel::Unit::Create(3));
102 while(nextMeasurement < measurements.
size()) {
115 throw runtime_error(
"Problem in data file, out-of-sequence measurements");
146 throw runtime_error(
"Problem in data file, out-of-sequence measurements");
156 double measuredRange =
measurement->measured().range();
157 newVariables.
insert(lmKey,
163 throw std::runtime_error(
"Unknown factor type read from data file");
167 gttoc_(Collect_measurements);
171 isam2.
update(newFactors, newVariables);
174 if(
step % 100 == 0) {
178 cout <<
"chi2 = " << chi2 << endl;
184 if(
step % 1000 == 0) {
185 cout <<
"Step " <<
step << endl;
232 gttic_(jointMarginalInformation);
237 gttoc_(jointMarginalInformation);
250 gttic_(marginalInformation);
252 gttoc_(marginalInformation);
256 }
catch(std::exception&
e) {
257 cout << e.what() << endl;
def step(data, isam, result, truth, currPoseIndex)
boost::shared_ptr< This > shared_ptr
void insert(Key j, const Value &val)
GraphAndValues load2D(const string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
NonlinearFactorGraph graph
NoiseModelFactor2< Pose, Pose > NM2
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
string findExampleDataFile(const string &name)
const Symbol key1('v', 1)
Values calculateEstimate() const
boost::shared_ptr< BetweenFactor > shared_ptr
int main(int argc, char *argv[])
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
NoiseModelFactor1< Pose > NM1
boost::shared_ptr< This > shared_ptr
JointMarginal jointMarginalInformation(const KeyVector &variables) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
double chi2_red(const gtsam::NonlinearFactorGraph &graph, const gtsam::Values &config)
GTSAM_EXPORT Point2 transformFrom(const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
void reverse(const MatrixType &m)
const Symbol key2('v', 2)
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)
A class for computing marginals in a NonlinearFactorGraph.
void tictoc_finishedIteration_()
const NonlinearFactorGraph & getFactorsUnsafe() const
utility functions for loading datasets
BearingRangeFactor< Pose, Point2 > BR
std::uint64_t Key
Integer nonlinear key type.
Marginals marginals(graph, result)
const Values & getLinearizationPoint() const
Access the current linearization point.
Matrix marginalInformation(Key variable) const