Go to the documentation of this file.
27 #include <boost/archive/binary_oarchive.hpp>
28 #include <boost/archive/binary_iarchive.hpp>
29 #include <boost/serialization/export.hpp>
32 using namespace gtsam;
62 for(
const std::shared_ptr<gtsam::NonlinearFactor>& nlf:
graph) {
63 graph_dim += nlf->dim();
65 double dof = graph_dim - config.
dim();
69 int main(
int argc,
char *argv[]) {
71 cout <<
"Loading data..." << endl;
76 std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr>
data =
83 cout <<
"Playing forward time steps..." << endl;
87 size_t nextMeasurement = 0;
94 gttic_(Collect_measurements);
99 newFactors.
addPrior(0,
Pose(), noiseModel::Unit::Create(3));
114 throw runtime_error(
"Problem in data file, out-of-sequence measurements");
145 throw runtime_error(
"Problem in data file, out-of-sequence measurements");
155 double measuredRange =
measurement->measured().range();
156 newVariables.
insert(lmKey,
162 throw std::runtime_error(
"Unknown factor type read from data file");
166 gttoc_(Collect_measurements);
170 isam2.
update(newFactors, newVariables);
173 if(
step % 100 == 0) {
177 cout <<
"chi2 = " << chi2 << endl;
183 if(
step % 1000 == 0) {
184 cout <<
"Step " <<
step << endl;
230 for (
auto it1 =
keys.rbegin(); it1 !=
keys.rend(); ++it1) {
233 for (
auto it2 =
keys.rbegin(); it2 !=
keys.rend(); ++it2) {
236 gttic_(jointMarginalInformation);
241 gttoc_(jointMarginalInformation);
254 gttic_(marginalInformation);
256 gttoc_(marginalInformation);
260 }
catch(std::exception&
e) {
261 cout <<
e.what() << endl;
const Symbol key1('v', 1)
std::shared_ptr< This > shared_ptr
JointMarginal jointMarginalInformation(const KeyVector &variables) const
BearingRangeFactor< Pose, Point2 > BR
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const NonlinearFactorGraph & getFactorsUnsafe() const
Matrix marginalInformation(Key variable) const
int main(int argc, char *argv[])
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
std::shared_ptr< This > shared_ptr
const Values & getLinearizationPoint() const
Access the current linearization point.
double error(const Values &values) const
const Symbol key2('v', 2)
utility functions for loading datasets
NoiseModelFactorN< Pose, Pose > NM2
void tictoc_finishedIteration_()
std::shared_ptr< BetweenFactor > shared_ptr
NoiseModelFactorN< Pose > NM1
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
def step(data, isam, result, truth, currPoseIndex, isamArgs=())
const gtsam::Symbol key('X', 0)
Values calculateEstimate() const
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
GraphAndValues load2D(const std::string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
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)
A class for computing marginals in a NonlinearFactorGraph.
std::vector< double > measurements
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in Pose coordinates and transforms it to world coordinates
void insert(Key j, const Value &val)
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
double chi2_red(const gtsam::NonlinearFactorGraph &graph, const gtsam::Values &config)
NonlinearFactorGraph graph
Marginals marginals(graph, result)
std::uint64_t Key
Integer nonlinear key type.
static Point2 measurement(323.0, 240.0)
a single factor contains both the bearing and the range to prevent handle to pair bearing and range f...
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:59