49 using namespace gtsam;
60 list<TimedOdometry> odometryList;
62 ifstream is(data_file.c_str());
65 double t, distance_traveled, delta_heading;
66 is >> t >> distance_traveled >> delta_heading;
67 odometryList.push_back(
78 vector<RangeTriple> triples;
80 ifstream is(data_file.c_str());
83 double t, sender, range;
85 is >> t >> sender >> receiver >> range;
93 int main (
int argc,
char** argv) {
100 size_t K = triples.size();
105 bool groundTruth =
false;
117 rangeNoise = robust ? tukey : gaussian;
124 M_PI - 2.02108900000000);
126 newFactors.
addPrior(0, pose0, priorNoise);
146 bool initialized =
false;
156 boost::tie(t, odometry) = timedOdometry;
163 lastPose = predictedPose;
164 initial.
insert(i, predictedPose);
167 while (k < K && t >= boost::get<0>(triples[k])) {
168 size_t j = boost::get<1>(triples[k]);
169 double range = boost::get<2>(triples[k]);
176 if ((k > minK) && (countK > incK)) {
178 gttic_(batchInitialization);
180 initial = batchOptimizer.
optimize();
181 gttoc_(batchInitialization);
185 isam.
update(newFactors, initial);
187 gttic_(calculateEstimate);
189 gttoc_(calculateEstimate);
list< TimedOdometry > readOdometry()
virtual const Values & optimize()
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
static shared_ptr Create(const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise)
boost::tuple< double, size_t, double > RangeTriple
pair< double, Pose2 > TimedOdometry
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
string findExampleDataFile(const string &name)
Values calculateEstimate() const
Class compose(const Class &g) const
const ValueType at(Key j) const
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
NonlinearISAM isam(relinearizeInterval)
Key symbol(unsigned char c, std::uint64_t j)
boost::shared_ptr< Base > shared_ptr
std::vector< float > Values
vector< RangeTriple > readTriples()
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
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)
noiseModel::Diagonal::shared_ptr priorNoise
Pose2 odometry(2.0, 0.0, 0.0)
int main(int argc, char **argv)
utility functions for loading datasets
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
All noise models live in the noiseModel namespace.