diff --git a/examples/VisualISAMExample.cpp b/examples/VisualISAMExample.cpp index 682ca1743..dca24dba5 100644 --- a/examples/VisualISAMExample.cpp +++ b/examples/VisualISAMExample.cpp @@ -72,8 +72,8 @@ int main(int argc, char* argv[]) { initials.insert(X(1), pose0Init*odoMeasurement); // Initial values for the landmarks, simulated with Gaussian noise - for (size_t j=0; jsample())); + for (size_t j=0; jsample())); // Update ISAM the first time and obtain the current estimate isam.update(newFactors, initials); diff --git a/examples/VisualSLAMData.h b/examples/VisualSLAMData.h index 1aa79324e..155a137d8 100644 --- a/examples/VisualSLAMData.h +++ b/examples/VisualSLAMData.h @@ -40,7 +40,7 @@ struct VisualSLAMExampleData { gtsam::shared_ptrK sK; // camera calibration parameters std::vector poses; // ground-truth camera poses gtsam::Pose3 odometry; // ground-truth odometry between 2 consecutive poses (simulated data for iSAM) - std::vector landmarks; // ground-truth landmarks + std::vector points; // ground-truth landmarks std::map > z; // 2D measurements of landmarks in each camera frame gtsam::SharedDiagonal noiseZ; // measurement noise (noiseModel::Isotropic::Sigma(2, 5.0f)); gtsam::SharedDiagonal noiseX; // noise for camera poses @@ -49,14 +49,14 @@ struct VisualSLAMExampleData { static const VisualSLAMExampleData generate() { VisualSLAMExampleData data; // Landmarks (ground truth) - data.landmarks.push_back(gtsam::Point3(10.0,10.0,10.0)); - data.landmarks.push_back(gtsam::Point3(-10.0,10.0,10.0)); - data.landmarks.push_back(gtsam::Point3(-10.0,-10.0,10.0)); - data.landmarks.push_back(gtsam::Point3(10.0,-10.0,10.0)); - data.landmarks.push_back(gtsam::Point3(10.0,10.0,-10.0)); - data.landmarks.push_back(gtsam::Point3(-10.0,10.0,-10.0)); - data.landmarks.push_back(gtsam::Point3(-10.0,-10.0,-10.0)); - data.landmarks.push_back(gtsam::Point3(10.0,-10.0,-10.0)); + data.points.push_back(gtsam::Point3(10.0,10.0,10.0)); + data.points.push_back(gtsam::Point3(-10.0,10.0,10.0)); + data.points.push_back(gtsam::Point3(-10.0,-10.0,10.0)); + data.points.push_back(gtsam::Point3(10.0,-10.0,10.0)); + data.points.push_back(gtsam::Point3(10.0,10.0,-10.0)); + data.points.push_back(gtsam::Point3(-10.0,10.0,-10.0)); + data.points.push_back(gtsam::Point3(-10.0,-10.0,-10.0)); + data.points.push_back(gtsam::Point3(10.0,-10.0,-10.0)); // Camera calibration parameters data.sK = gtsam::shared_ptrK(new gtsam::Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)); @@ -65,8 +65,7 @@ struct VisualSLAMExampleData { int n = 8; double theta = 0.0; double r = 30.0; - for (int i=0; isample())); + data.z[i].push_back(camera.project(data.points[j]) + gtsam::Point2(data.noiseZ->sample())); } } - data.noiseX = gtsam::sharedSigmas(gtsam::Vector_(6, 0.01, 0.01, 0.01, 0.1, 0.1, 0.1)); + data.noiseX = gtsam::sharedSigmas(gtsam::Vector_(6, 0.001, 0.001, 0.001, 0.1, 0.1, 0.1)); data.noiseL = gtsam::sharedSigma(3, 0.1); return data; diff --git a/examples/VisualSLAMExample.cpp b/examples/VisualSLAMExample.cpp index 0dcd970e4..90391bf90 100644 --- a/examples/VisualSLAMExample.cpp +++ b/examples/VisualSLAMExample.cpp @@ -39,18 +39,19 @@ int main(int argc, char* argv[]) { /* 2. Add factors to the graph */ // 2a. Measurement factors for (size_t i=0; isample())); - for (size_t j=0; jsample())); + for (size_t j=0; jsample())); initial.print("Intial Estimates: "); /* 4. Optimize the graph and print results */