diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 052bb3343..66e8fc4c0 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -37,6 +37,7 @@ #include #include #include +#include #include #include @@ -541,10 +542,16 @@ std::map parse3DPoses(const string& filename) { } /* ************************************************************************* */ -BetweenFactorPose3s parse3DFactors(const string& filename) { +BetweenFactorPose3s parse3DFactors(const string& filename, + const noiseModel::Diagonal::shared_ptr& corruptingNoise) { ifstream is(filename.c_str()); if (!is) throw invalid_argument("parse3DFactors: can not find file " + filename); + boost::optional sampler; + if (corruptingNoise) { + sampler = Sampler(corruptingNoise); + } + std::vector::shared_ptr> factors; while (!is.eof()) { char buf[LINESIZE]; @@ -585,8 +592,13 @@ BetweenFactorPose3s parse3DFactors(const string& filename) { mgtsam.block<3, 3>(3, 0) = m.block<3, 3>(3, 0); // off diagonal SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); + auto R12 = Rot3::Quaternion(qw, qx, qy, qz); + if (sampler) { + R12 = R12.retract(sampler->sample()); + } + factors.emplace_back(new BetweenFactor( - id1, id2, Pose3(Rot3::Quaternion(qw, qx, qy, qz), {x, y, z}), model)); + id1, id2, Pose3(R12, {x, y, z}), model)); } } return factors; diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 3ab199bab..032799429 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -159,7 +159,8 @@ GTSAM_EXPORT void writeG2o(const NonlinearFactorGraph& graph, /// Parse edges in 3D TORO graph file into a set of BetweenFactors. using BetweenFactorPose3s = std::vector::shared_ptr>; -GTSAM_EXPORT BetweenFactorPose3s parse3DFactors(const std::string& filename); +GTSAM_EXPORT BetweenFactorPose3s parse3DFactors(const std::string& filename, + const noiseModel::Diagonal::shared_ptr& corruptingNoise=nullptr); /// Parse vertices in 3D TORO graph file into a map of Pose3s. GTSAM_EXPORT std::map parse3DPoses(const std::string& filename);