commit
93b9d32ff9
|
@ -0,0 +1,6 @@
|
||||||
|
VERTEX_SE3:QUAT 0 -3.865747774038187 0.06639337702667497 -0.16064874691945374 0.024595211709139555 0.49179523413089893 -0.06279232989379242 0.8680954132776109
|
||||||
|
VERTEX_SE3:QUAT 1 -3.614793159814815 0.04774490041587656 -0.2837650367985949 0.00991721787943912 0.4854918961891193 -0.042343290945895576 0.8731588132957809
|
||||||
|
VERTEX_SE3:QUAT 2 -3.255096913553434 0.013296754286114112 -0.5339792269680574 -0.027851108010665374 0.585478168397957 -0.05088341463532465 0.8086102325762403
|
||||||
|
EDGE_SE3:QUAT 0 1 0.2509546142233723 -0.01864847661079841 -0.12311628987914114 -0.022048798853273946 -0.01796327847857683 0.010210006313668573 0.9995433591728293 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0
|
||||||
|
EDGE_SE3:QUAT 0 2 0.6106508604847534 -0.05309662274056086 -0.3733304800486037 -0.054972994022992064 0.10432547598981769 -0.02221474884651081 0.9927742290779572 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0
|
||||||
|
EDGE_SE3:QUAT 1 2 0.3596962462613811 -0.03444814612976245 -0.25021419016946256 -0.03174661848656213 0.11646825423134777 -0.02951742735854383 0.9922479626852876 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0
|
|
@ -0,0 +1,11 @@
|
||||||
|
VERTEX_SE3:QUAT 0 0 0 0 0 0 0 1
|
||||||
|
VERTEX_SE3:QUAT 1 0 0 0 0 0 0 1
|
||||||
|
VERTEX_SE3:QUAT 2 0 0 0 0.00499994 0.00499994 0.00499994 0.999963
|
||||||
|
VERTEX_SE3:QUAT 3 0 0 0 -0.00499994 -0.00499994 -0.00499994 0.999963
|
||||||
|
VERTEX_SE3:QUAT 4 0 0 0 0.00499994 0.00499994 0.00499994 0.999963
|
||||||
|
EDGE_SE3:QUAT 1 2 1 2 0 0 0 0.707107 0.707107 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100
|
||||||
|
EDGE_SE3:QUAT 2 3 -3.26795e-07 1 0 0 0 0.707107 0.707107 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100
|
||||||
|
EDGE_SE3:QUAT 3 4 1 1 0 0 0 0.707107 0.707107 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100
|
||||||
|
EDGE_SE3:QUAT 3 1 6.9282e-07 2 0 0 0 1 1.73205e-07 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100
|
||||||
|
EDGE_SE3:QUAT 1 4 -1 1 0 0 0 -0.707107 0.707107 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100
|
||||||
|
EDGE_SE3:QUAT 0 1 0 0 0 0 0 0 1 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100
|
|
@ -442,11 +442,11 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate,
|
||||||
auto p = dynamic_cast<const GenericValue<Pose3>*>(&key_value.value);
|
auto p = dynamic_cast<const GenericValue<Pose3>*>(&key_value.value);
|
||||||
if (!p) continue;
|
if (!p) continue;
|
||||||
const Pose3& pose = p->value();
|
const Pose3& pose = p->value();
|
||||||
Point3 t = pose.translation();
|
const Point3 t = pose.translation();
|
||||||
Rot3 R = pose.rotation();
|
const auto q = pose.rotation().toQuaternion();
|
||||||
stream << "VERTEX_SE3:QUAT " << key_value.key << " " << t.x() << " " << t.y() << " " << t.z()
|
stream << "VERTEX_SE3:QUAT " << key_value.key << " " << t.x() << " "
|
||||||
<< " " << R.toQuaternion().x() << " " << R.toQuaternion().y() << " " << R.toQuaternion().z()
|
<< t.y() << " " << t.z() << " " << q.x() << " " << q.y() << " "
|
||||||
<< " " << R.toQuaternion().w() << endl;
|
<< q.z() << " " << q.w() << endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
// save edges (2D or 3D)
|
// save edges (2D or 3D)
|
||||||
|
@ -486,13 +486,12 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate,
|
||||||
throw invalid_argument("writeG2o: invalid noise model!");
|
throw invalid_argument("writeG2o: invalid noise model!");
|
||||||
}
|
}
|
||||||
Matrix Info = gaussianModel->R().transpose() * gaussianModel->R();
|
Matrix Info = gaussianModel->R().transpose() * gaussianModel->R();
|
||||||
Pose3 pose3D = factor3D->measured();
|
const Pose3 pose3D = factor3D->measured();
|
||||||
Point3 p = pose3D.translation();
|
const Point3 p = pose3D.translation();
|
||||||
Rot3 R = pose3D.rotation();
|
const auto q = pose3D.rotation().toQuaternion();
|
||||||
|
stream << "EDGE_SE3:QUAT " << factor3D->key1() << " " << factor3D->key2()
|
||||||
stream << "EDGE_SE3:QUAT " << factor3D->key1() << " " << factor3D->key2() << " "
|
<< " " << p.x() << " " << p.y() << " " << p.z() << " " << q.x()
|
||||||
<< p.x() << " " << p.y() << " " << p.z() << " " << R.toQuaternion().x()
|
<< " " << q.y() << " " << q.z() << " " << q.w();
|
||||||
<< " " << R.toQuaternion().y() << " " << R.toQuaternion().z() << " " << R.toQuaternion().w();
|
|
||||||
|
|
||||||
Matrix InfoG2o = I_6x6;
|
Matrix InfoG2o = I_6x6;
|
||||||
InfoG2o.block(0,0,3,3) = Info.block(3,3,3,3); // cov translation
|
InfoG2o.block(0,0,3,3) = Info.block(3,3,3,3); // cov translation
|
||||||
|
@ -511,6 +510,11 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate,
|
||||||
stream.close();
|
stream.close();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
static Rot3 NormalizedRot3(double w, double x, double y, double z) {
|
||||||
|
const double norm = sqrt(w * w + x * x + y * y + z * z), f = 1.0 / norm;
|
||||||
|
return Rot3::Quaternion(f * w, f * x, f * y, f * z);
|
||||||
|
}
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
std::map<Key, Pose3> parse3DPoses(const string& filename) {
|
std::map<Key, Pose3> parse3DPoses(const string& filename) {
|
||||||
ifstream is(filename.c_str());
|
ifstream is(filename.c_str());
|
||||||
|
@ -535,14 +539,15 @@ std::map<Key, Pose3> parse3DPoses(const string& filename) {
|
||||||
Key id;
|
Key id;
|
||||||
double x, y, z, qx, qy, qz, qw;
|
double x, y, z, qx, qy, qz, qw;
|
||||||
ls >> id >> x >> y >> z >> qx >> qy >> qz >> qw;
|
ls >> id >> x >> y >> z >> qx >> qy >> qz >> qw;
|
||||||
poses.emplace(id, Pose3(Rot3::Quaternion(qw, qx, qy, qz), {x, y, z}));
|
poses.emplace(id, Pose3(NormalizedRot3(qw, qx, qy, qz), {x, y, z}));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return poses;
|
return poses;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
BetweenFactorPose3s parse3DFactors(const string& filename,
|
BetweenFactorPose3s parse3DFactors(
|
||||||
|
const string& filename,
|
||||||
const noiseModel::Diagonal::shared_ptr& corruptingNoise) {
|
const noiseModel::Diagonal::shared_ptr& corruptingNoise) {
|
||||||
ifstream is(filename.c_str());
|
ifstream is(filename.c_str());
|
||||||
if (!is) throw invalid_argument("parse3DFactors: can not find file " + filename);
|
if (!is) throw invalid_argument("parse3DFactors: can not find file " + filename);
|
||||||
|
@ -592,7 +597,7 @@ BetweenFactorPose3s parse3DFactors(const string& filename,
|
||||||
mgtsam.block<3, 3>(3, 0) = m.block<3, 3>(3, 0); // off diagonal
|
mgtsam.block<3, 3>(3, 0) = m.block<3, 3>(3, 0); // off diagonal
|
||||||
|
|
||||||
SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam);
|
SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam);
|
||||||
auto R12 = Rot3::Quaternion(qw, qx, qy, qz);
|
auto R12 = NormalizedRot3(qw, qx, qy, qz);
|
||||||
if (sampler) {
|
if (sampler) {
|
||||||
R12 = R12.retract(sampler->sample());
|
R12 = R12.retract(sampler->sample());
|
||||||
}
|
}
|
||||||
|
|
|
@ -122,45 +122,6 @@ TEST( dataSet, Balbianello)
|
||||||
EXPECT(assert_equal(expected,actual,1));
|
EXPECT(assert_equal(expected,actual,1));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
TEST( dataSet, readG2o)
|
|
||||||
{
|
|
||||||
const string g2oFile = findExampleDataFile("pose2example");
|
|
||||||
NonlinearFactorGraph::shared_ptr actualGraph;
|
|
||||||
Values::shared_ptr actualValues;
|
|
||||||
boost::tie(actualGraph, actualValues) = readG2o(g2oFile);
|
|
||||||
|
|
||||||
Values expectedValues;
|
|
||||||
expectedValues.insert(0, Pose2(0.000000, 0.000000, 0.000000));
|
|
||||||
expectedValues.insert(1, Pose2(1.030390, 0.011350, -0.081596));
|
|
||||||
expectedValues.insert(2, Pose2(2.036137, -0.129733, -0.301887));
|
|
||||||
expectedValues.insert(3, Pose2(3.015097, -0.442395, -0.345514));
|
|
||||||
expectedValues.insert(4, Pose2(3.343949, 0.506678, 1.214715));
|
|
||||||
expectedValues.insert(5, Pose2(3.684491, 1.464049, 1.183785));
|
|
||||||
expectedValues.insert(6, Pose2(4.064626, 2.414783, 1.176333));
|
|
||||||
expectedValues.insert(7, Pose2(4.429778, 3.300180, 1.259169));
|
|
||||||
expectedValues.insert(8, Pose2(4.128877, 2.321481, -1.825391));
|
|
||||||
expectedValues.insert(9, Pose2(3.884653, 1.327509, -1.953016));
|
|
||||||
expectedValues.insert(10, Pose2(3.531067, 0.388263, -2.148934));
|
|
||||||
EXPECT(assert_equal(expectedValues,*actualValues,1e-5));
|
|
||||||
|
|
||||||
noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Precisions(Vector3(44.721360, 44.721360, 30.901699));
|
|
||||||
NonlinearFactorGraph expectedGraph;
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(0, 1, Pose2(1.030390, 0.011350, -0.081596), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(1, 2, Pose2(1.013900, -0.058639, -0.220291), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(2, 3, Pose2(1.027650, -0.007456, -0.043627), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(3, 4, Pose2(-0.012016, 1.004360, 1.560229), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(4, 5, Pose2(1.016030, 0.014565, -0.030930), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(5, 6, Pose2(1.023890, 0.006808, -0.007452), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(6, 7, Pose2(0.957734, 0.003159, 0.082836), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(7, 8, Pose2(-1.023820, -0.013668, -3.084560), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(8, 9, Pose2(1.023440, 0.013984, -0.127624), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(9,10, Pose2(1.003350, 0.022250, -0.195918), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(5, 9, Pose2(0.033943, 0.032439, 3.073637), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(3,10, Pose2(0.044020, 0.988477, -1.553511), model);
|
|
||||||
EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5));
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST(dataSet, readG2o3D) {
|
TEST(dataSet, readG2o3D) {
|
||||||
const string g2oFile = findExampleDataFile("pose3example");
|
const string g2oFile = findExampleDataFile("pose3example");
|
||||||
|
@ -273,59 +234,103 @@ TEST( dataSet, readG2o3DNonDiagonalNoise)
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST( dataSet, readG2oHuber)
|
TEST(dataSet, readG2oCheckDeterminants) {
|
||||||
{
|
const string g2oFile = findExampleDataFile("toyExample.g2o");
|
||||||
const string g2oFile = findExampleDataFile("pose2example");
|
|
||||||
NonlinearFactorGraph::shared_ptr actualGraph;
|
|
||||||
Values::shared_ptr actualValues;
|
|
||||||
bool is3D = false;
|
|
||||||
boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D, KernelFunctionTypeHUBER);
|
|
||||||
|
|
||||||
noiseModel::Diagonal::shared_ptr baseModel = noiseModel::Diagonal::Precisions(Vector3(44.721360, 44.721360, 30.901699));
|
// Check determinants in factors
|
||||||
SharedNoiseModel model = noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(1.345), baseModel);
|
auto factors = parse3DFactors(g2oFile);
|
||||||
|
EXPECT_LONGS_EQUAL(6, factors.size());
|
||||||
|
for (const auto& factor : factors) {
|
||||||
|
const Rot3 R = factor->measured().rotation();
|
||||||
|
EXPECT_DOUBLES_EQUAL(1.0, R.matrix().determinant(), 1e-9);
|
||||||
|
}
|
||||||
|
|
||||||
NonlinearFactorGraph expectedGraph;
|
// Check determinants in initial values
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(0, 1, Pose2(1.030390, 0.011350, -0.081596), model);
|
const map<Key, Pose3> poses = parse3DPoses(g2oFile);
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(1, 2, Pose2(1.013900, -0.058639, -0.220291), model);
|
EXPECT_LONGS_EQUAL(5, poses.size());
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(2, 3, Pose2(1.027650, -0.007456, -0.043627), model);
|
for (const auto& key_value : poses) {
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(3, 4, Pose2(-0.012016, 1.004360, 1.560229), model);
|
const Rot3 R = key_value.second.rotation();
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(4, 5, Pose2(1.016030, 0.014565, -0.030930), model);
|
EXPECT_DOUBLES_EQUAL(1.0, R.matrix().determinant(), 1e-9);
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(5, 6, Pose2(1.023890, 0.006808, -0.007452), model);
|
}
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(6, 7, Pose2(0.957734, 0.003159, 0.082836), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(7, 8, Pose2(-1.023820, -0.013668, -3.084560), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(8, 9, Pose2(1.023440, 0.013984, -0.127624), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(9,10, Pose2(1.003350, 0.022250, -0.195918), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(5, 9, Pose2(0.033943, 0.032439, 3.073637), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(3,10, Pose2(0.044020, 0.988477, -1.553511), model);
|
|
||||||
EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST( dataSet, readG2oTukey)
|
static NonlinearFactorGraph expectedGraph(const SharedNoiseModel& model) {
|
||||||
{
|
NonlinearFactorGraph g;
|
||||||
|
using Factor = BetweenFactor<Pose2>;
|
||||||
|
g.emplace_shared<Factor>(0, 1, Pose2(1.030390, 0.011350, -0.081596), model);
|
||||||
|
g.emplace_shared<Factor>(1, 2, Pose2(1.013900, -0.058639, -0.220291), model);
|
||||||
|
g.emplace_shared<Factor>(2, 3, Pose2(1.027650, -0.007456, -0.043627), model);
|
||||||
|
g.emplace_shared<Factor>(3, 4, Pose2(-0.012016, 1.004360, 1.560229), model);
|
||||||
|
g.emplace_shared<Factor>(4, 5, Pose2(1.016030, 0.014565, -0.030930), model);
|
||||||
|
g.emplace_shared<Factor>(5, 6, Pose2(1.023890, 0.006808, -0.007452), model);
|
||||||
|
g.emplace_shared<Factor>(6, 7, Pose2(0.957734, 0.003159, 0.082836), model);
|
||||||
|
g.emplace_shared<Factor>(7, 8, Pose2(-1.023820, -0.013668, -3.084560), model);
|
||||||
|
g.emplace_shared<Factor>(8, 9, Pose2(1.023440, 0.013984, -0.127624), model);
|
||||||
|
g.emplace_shared<Factor>(9, 10, Pose2(1.003350, 0.022250, -0.195918), model);
|
||||||
|
g.emplace_shared<Factor>(5, 9, Pose2(0.033943, 0.032439, 3.073637), model);
|
||||||
|
g.emplace_shared<Factor>(3, 10, Pose2(0.044020, 0.988477, -1.553511), model);
|
||||||
|
return g;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
TEST(dataSet, readG2o) {
|
||||||
|
const string g2oFile = findExampleDataFile("pose2example");
|
||||||
|
NonlinearFactorGraph::shared_ptr actualGraph;
|
||||||
|
Values::shared_ptr actualValues;
|
||||||
|
boost::tie(actualGraph, actualValues) = readG2o(g2oFile);
|
||||||
|
|
||||||
|
auto model = noiseModel::Diagonal::Precisions(
|
||||||
|
Vector3(44.721360, 44.721360, 30.901699));
|
||||||
|
EXPECT(assert_equal(expectedGraph(model), *actualGraph, 1e-5));
|
||||||
|
|
||||||
|
Values expectedValues;
|
||||||
|
expectedValues.insert(0, Pose2(0.000000, 0.000000, 0.000000));
|
||||||
|
expectedValues.insert(1, Pose2(1.030390, 0.011350, -0.081596));
|
||||||
|
expectedValues.insert(2, Pose2(2.036137, -0.129733, -0.301887));
|
||||||
|
expectedValues.insert(3, Pose2(3.015097, -0.442395, -0.345514));
|
||||||
|
expectedValues.insert(4, Pose2(3.343949, 0.506678, 1.214715));
|
||||||
|
expectedValues.insert(5, Pose2(3.684491, 1.464049, 1.183785));
|
||||||
|
expectedValues.insert(6, Pose2(4.064626, 2.414783, 1.176333));
|
||||||
|
expectedValues.insert(7, Pose2(4.429778, 3.300180, 1.259169));
|
||||||
|
expectedValues.insert(8, Pose2(4.128877, 2.321481, -1.825391));
|
||||||
|
expectedValues.insert(9, Pose2(3.884653, 1.327509, -1.953016));
|
||||||
|
expectedValues.insert(10, Pose2(3.531067, 0.388263, -2.148934));
|
||||||
|
EXPECT(assert_equal(expectedValues, *actualValues, 1e-5));
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
TEST(dataSet, readG2oHuber) {
|
||||||
const string g2oFile = findExampleDataFile("pose2example");
|
const string g2oFile = findExampleDataFile("pose2example");
|
||||||
NonlinearFactorGraph::shared_ptr actualGraph;
|
NonlinearFactorGraph::shared_ptr actualGraph;
|
||||||
Values::shared_ptr actualValues;
|
Values::shared_ptr actualValues;
|
||||||
bool is3D = false;
|
bool is3D = false;
|
||||||
boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D, KernelFunctionTypeTUKEY);
|
boost::tie(actualGraph, actualValues) =
|
||||||
|
readG2o(g2oFile, is3D, KernelFunctionTypeHUBER);
|
||||||
|
|
||||||
noiseModel::Diagonal::shared_ptr baseModel = noiseModel::Diagonal::Precisions(Vector3(44.721360, 44.721360, 30.901699));
|
auto baseModel = noiseModel::Diagonal::Precisions(
|
||||||
SharedNoiseModel model = noiseModel::Robust::Create(noiseModel::mEstimator::Tukey::Create(4.6851), baseModel);
|
Vector3(44.721360, 44.721360, 30.901699));
|
||||||
|
auto model = noiseModel::Robust::Create(
|
||||||
|
noiseModel::mEstimator::Huber::Create(1.345), baseModel);
|
||||||
|
|
||||||
NonlinearFactorGraph expectedGraph;
|
EXPECT(assert_equal(expectedGraph(model), *actualGraph, 1e-5));
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(0, 1, Pose2(1.030390, 0.011350, -0.081596), model);
|
}
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(1, 2, Pose2(1.013900, -0.058639, -0.220291), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(2, 3, Pose2(1.027650, -0.007456, -0.043627), model);
|
/* ************************************************************************* */
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(3, 4, Pose2(-0.012016, 1.004360, 1.560229), model);
|
TEST(dataSet, readG2oTukey) {
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(4, 5, Pose2(1.016030, 0.014565, -0.030930), model);
|
const string g2oFile = findExampleDataFile("pose2example");
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(5, 6, Pose2(1.023890, 0.006808, -0.007452), model);
|
NonlinearFactorGraph::shared_ptr actualGraph;
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(6, 7, Pose2(0.957734, 0.003159, 0.082836), model);
|
Values::shared_ptr actualValues;
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(7, 8, Pose2(-1.023820, -0.013668, -3.084560), model);
|
bool is3D = false;
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(8, 9, Pose2(1.023440, 0.013984, -0.127624), model);
|
boost::tie(actualGraph, actualValues) =
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(9,10, Pose2(1.003350, 0.022250, -0.195918), model);
|
readG2o(g2oFile, is3D, KernelFunctionTypeTUKEY);
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(5, 9, Pose2(0.033943, 0.032439, 3.073637), model);
|
|
||||||
expectedGraph.emplace_shared<BetweenFactor<Pose2> >(3,10, Pose2(0.044020, 0.988477, -1.553511), model);
|
auto baseModel = noiseModel::Diagonal::Precisions(
|
||||||
EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5));
|
Vector3(44.721360, 44.721360, 30.901699));
|
||||||
|
auto model = noiseModel::Robust::Create(
|
||||||
|
noiseModel::mEstimator::Tukey::Create(4.6851), baseModel);
|
||||||
|
|
||||||
|
EXPECT(assert_equal(expectedGraph(model), *actualGraph, 1e-5));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -495,7 +500,7 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){
|
||||||
SfmData readData;
|
SfmData readData;
|
||||||
readBAL(filenameToRead, readData);
|
readBAL(filenameToRead, readData);
|
||||||
|
|
||||||
Pose3 poseChange = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.3,0.1,0.3));
|
Pose3 poseChange = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.3,0.1,0.3));
|
||||||
|
|
||||||
Values value;
|
Values value;
|
||||||
for(size_t i=0; i < readData.number_cameras(); i++){ // for each camera
|
for(size_t i=0; i < readData.number_cameras(); i++){ // for each camera
|
||||||
|
|
Loading…
Reference in New Issue