51 using namespace gtsam;
62 list<TimedOdometry> odometryList;
65 if (!is)
throw runtime_error(
"Plaza2_DR.txt file not found");
68 double t, distance_traveled, delta_heading;
69 is >> t >> distance_traveled >> delta_heading;
70 odometryList.push_back(
81 vector<RangeTriple> triples;
84 if (!is)
throw runtime_error(
"Plaza2_TD.txt file not found");
87 double t, sender, receiver, range;
88 is >> t >> sender >> receiver >> range;
96 int main(
int argc,
char** argv) {
103 size_t K = triples.size();
118 rangeNoise = robust ? tukey : gaussian;
124 Pose2 pose0 =
Pose2(-34.2086489999201, 45.3007639991120, -2.02108900000000);
126 newFactors.
addPrior(0, pose0, priorNoise);
149 boost::tie(t, odometry) = timedOdometry;
158 lastPose = predictedPose;
159 initial.
insert(i, predictedPose);
160 landmarkEstimates.
insert(i, predictedPose);
163 while (k < K && t >= boost::get<0>(triples[k])) {
164 size_t j = boost::get<1>(triples[k]);
165 double range = boost::get<2>(triples[k]);
168 Vector error = factor.unwhitenedError(landmarkEstimates);
169 if (k <= 200 ||
std::abs(error[0]) < 5)
178 isam.
update(newFactors, initial);
180 gttic_(calculateEstimate);
182 gttoc_(calculateEstimate);
185 landmarkEstimates =
Values();
186 landmarkEstimates.insert(
symbol(
'L', 1), result.
at(
symbol(
'L', 1)));
187 landmarkEstimates.insert(
symbol(
'L', 6), result.
at(
symbol(
'L', 6)));
188 landmarkEstimates.insert(
symbol(
'L', 0), result.
at(
symbol(
'L', 0)));
189 landmarkEstimates.insert(
symbol(
'L', 5), result.
at(
symbol(
'L', 5)));
204 ofstream os2(
"rangeResultLM.txt");
206 os2 << it.key <<
"\t" << it.value.x() <<
"\t" << it.value.y() <<
"\t1" 208 ofstream
os(
"rangeResult.txt");
210 os << it.key <<
"\t" << it.value.x() <<
"\t" << it.value.y() <<
"\t" 211 << it.value.theta() << endl;
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)
boost::tuple< double, size_t, double > RangeTriple
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)
pair< double, Pose2 > TimedOdometry
vector< RangeTriple > readTriples()
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
list< TimedOdometry > readOdometry()
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
int main(int argc, char **argv)
std::vector< float > Values
pair< double, Pose2 > TimedOdometry
ofstream os("timeSchurFactors.csv")
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)
utility functions for loading datasets
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Filtered< Value > filter(const boost::function< bool(Key)> &filterFcn)
All noise models live in the noiseModel namespace.