/* ---------------------------------------------------------------------------- * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) * See LICENSE for the license information * -------------------------------------------------------------------------- */ /** * @file TestSmartStereoProjectionPoseFactor.cpp * @brief Unit tests for ProjectionFactor Class * @author Chris Beall * @author Luca Carlone * @author Zsolt Kira * @date Sept 2013 */ // TODO #include #include #include #include #include #include #include #include #include using namespace std; using namespace boost::assign; using namespace gtsam; // make a realistic calibration matrix static double fov = 60; // degrees static size_t w = 640, h = 480; static double b = 1; static Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fov, w, h, b)); static Cal3_S2Stereo::shared_ptr K2( new Cal3_S2Stereo(1500, 1200, 0, 640, 480, b)); static SmartStereoProjectionParams params; // static bool manageDegeneracy = true; // Create a noise model for the pixel error static SharedNoiseModel model(noiseModel::Isotropic::Sigma(3, 0.1)); // Convenience for named keys using symbol_shorthand::X; using symbol_shorthand::L; // tests data static Symbol x1('X', 1); static Symbol x2('X', 2); static Symbol x3('X', 3); static Key poseKey1(x1); static StereoPoint2 measurement1(323.0, 300.0, 240.0); //potentially use more reasonable measurement value? static Pose3 body_P_sensor1(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); vector stereo_projectToMultipleCameras(const StereoCamera& cam1, const StereoCamera& cam2, const StereoCamera& cam3, Point3 landmark) { vector measurements_cam; StereoPoint2 cam1_uv1 = cam1.project(landmark); StereoPoint2 cam2_uv1 = cam2.project(landmark); StereoPoint2 cam3_uv1 = cam3.project(landmark); measurements_cam.push_back(cam1_uv1); measurements_cam.push_back(cam2_uv1); measurements_cam.push_back(cam3_uv1); return measurements_cam; } LevenbergMarquardtParams lm_params; /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Constructor) { SmartStereoProjectionPoseFactor::shared_ptr factor1(new SmartStereoProjectionPoseFactor()); } /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Constructor2) { SmartStereoProjectionPoseFactor factor1(params); } /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Constructor3) { SmartStereoProjectionPoseFactor::shared_ptr factor1(new SmartStereoProjectionPoseFactor()); factor1->add(measurement1, poseKey1, model, K); } /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Constructor4) { SmartStereoProjectionPoseFactor factor1(params); factor1.add(measurement1, poseKey1, model, K); } /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Equals ) { SmartStereoProjectionPoseFactor::shared_ptr factor1(new SmartStereoProjectionPoseFactor()); factor1->add(measurement1, poseKey1, model, K); SmartStereoProjectionPoseFactor::shared_ptr factor2(new SmartStereoProjectionPoseFactor()); factor2->add(measurement1, poseKey1, model, K); CHECK(assert_equal(*factor1, *factor2)); } /* *************************************************************************/ TEST_UNSAFE( SmartStereoProjectionPoseFactor, noiseless ) { // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera level_camera(level_pose, K2); // create second camera 1 meter to the right of first camera Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0)); StereoCamera level_camera_right(level_pose_right, K2); // landmark ~5 meters infront of camera Point3 landmark(5, 0.5, 1.2); // 1. Project two landmarks into two cameras and triangulate StereoPoint2 level_uv = level_camera.project(landmark); StereoPoint2 level_uv_right = level_camera_right.project(landmark); Values values; values.insert(x1, level_pose); values.insert(x2, level_pose_right); SmartStereoProjectionPoseFactor factor1; factor1.add(level_uv, x1, model, K2); factor1.add(level_uv_right, x2, model, K2); double actualError = factor1.error(values); double expectedError = 0.0; EXPECT_DOUBLES_EQUAL(expectedError, actualError, 1e-7); SmartStereoProjectionPoseFactor::Cameras cameras = factor1.cameras(values); double actualError2 = factor1.totalReprojectionError(cameras); EXPECT_DOUBLES_EQUAL(expectedError, actualError2, 1e-7); // test vector of errors //Vector actual = factor1.unwhitenedError(values); //EXPECT(assert_equal(zero(4),actual,1e-8)); } /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, noisy ) { // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera level_camera(level_pose, K2); // create second camera 1 meter to the right of first camera Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0)); StereoCamera level_camera_right(level_pose_right, K2); // landmark ~5 meters infront of camera Point3 landmark(5, 0.5, 1.2); // 1. Project two landmarks into two cameras and triangulate StereoPoint2 pixelError(0.2, 0.2, 0); StereoPoint2 level_uv = level_camera.project(landmark) + pixelError; StereoPoint2 level_uv_right = level_camera_right.project(landmark); Values values; values.insert(x1, level_pose); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); values.insert(x2, level_pose_right.compose(noise_pose)); SmartStereoProjectionPoseFactor::shared_ptr factor1(new SmartStereoProjectionPoseFactor()); factor1->add(level_uv, x1, model, K); factor1->add(level_uv_right, x2, model, K); double actualError1 = factor1->error(values); SmartStereoProjectionPoseFactor::shared_ptr factor2(new SmartStereoProjectionPoseFactor()); vector measurements; measurements.push_back(level_uv); measurements.push_back(level_uv_right); vector noises; noises.push_back(model); noises.push_back(model); vector > Ks; ///< shared pointer to calibration object (one for each camera) Ks.push_back(K); Ks.push_back(K); vector views; views.push_back(x1); views.push_back(x2); factor2->add(measurements, views, noises, Ks); double actualError2 = factor2->error(values); DOUBLES_EQUAL(actualError1, actualError2, 1e-7); } /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K2); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); StereoCamera cam2(pose2, K2); // create third camera 1 meter above the first camera Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); StereoCamera cam3(pose3, K2); // three landmarks ~5 meters infront of camera Point3 landmark1(5, 0.5, 1.2); Point3 landmark2(5, -0.5, 1.2); Point3 landmark3(3, 0, 3.0); // 1. Project three landmarks into three cameras and triangulate vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor()); smartFactor1->add(measurements_cam1, views, model, K2); SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor()); smartFactor2->add(measurements_cam2, views, model, K2); SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor()); smartFactor3->add(measurements_cam3, views, model, K2); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); graph.push_back(PriorFactor(x1, pose1, noisePrior)); graph.push_back(PriorFactor(x2, pose2, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, pose1); values.insert(x2, pose2); // initialize third pose with some noise, we expect it to move back to original pose3 values.insert(x3, pose3 * noise_pose); EXPECT( assert_equal( Pose3( Rot3(0, -0.0314107591, 0.99950656, -0.99950656, -0.0313952598, -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598), Point3(0.1, -0.1, 1.9)), values.at(x3))); EXPECT_DOUBLES_EQUAL(979345.4, graph.error(values), 1); Values result; gttic_(SmartStereoProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); result = optimizer.optimize(); gttoc_(SmartStereoProjectionPoseFactor); tictoc_finishedIteration_(); EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-5); GaussianFactorGraph::shared_ptr GFG = graph.linearize(result); VectorValues delta = GFG->optimize(); VectorValues expected = VectorValues::Zero(delta); EXPECT(assert_equal(expected, delta, 1e-6)); // result.print("results of 3 camera, 3 landmark optimization \n"); EXPECT(assert_equal(pose3, result.at(x3))); } /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, jacobianSVD ) { vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); StereoCamera cam2(pose2, K); // create third camera 1 meter above the first camera Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); StereoCamera cam3(pose3, K); // three landmarks ~5 meters infront of camera Point3 landmark1(5, 0.5, 1.2); Point3 landmark2(5, -0.5, 1.2); Point3 landmark3(3, 0, 3.0); // 1. Project three landmarks into three cameras and triangulate vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); SmartStereoProjectionParams params; params.setLinearizationMode(JACOBIAN_SVD); SmartStereoProjectionPoseFactor::shared_ptr smartFactor1( new SmartStereoProjectionPoseFactor(params)); smartFactor1->add(measurements_cam1, views, model, K); SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(params)); smartFactor2->add(measurements_cam2, views, model, K); SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(params)); smartFactor3->add(measurements_cam3, views, model, K); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); graph.push_back(PriorFactor(x1, pose1, noisePrior)); graph.push_back(PriorFactor(x2, pose2, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, pose1); values.insert(x2, pose2); values.insert(x3, pose3 * noise_pose); Values result; LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); result = optimizer.optimize(); EXPECT(assert_equal(pose3, result.at(x3))); } /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) { // double excludeLandmarksFutherThanDist = 2; vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); StereoCamera cam2(pose2, K); // create third camera 1 meter above the first camera Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); StereoCamera cam3(pose3, K); // three landmarks ~5 meters infront of camera Point3 landmark1(5, 0.5, 1.2); Point3 landmark2(5, -0.5, 1.2); Point3 landmark3(3, 0, 3.0); // 1. Project three landmarks into three cameras and triangulate vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); SmartStereoProjectionParams params; params.setLinearizationMode(JACOBIAN_SVD); params.setLandmarkDistanceThreshold(2); SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(params)); smartFactor1->add(measurements_cam1, views, model, K); SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(params)); smartFactor2->add(measurements_cam2, views, model, K); SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(params)); smartFactor3->add(measurements_cam3, views, model, K); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); graph.push_back(PriorFactor(x1, pose1, noisePrior)); graph.push_back(PriorFactor(x2, pose2, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, pose1); values.insert(x2, pose2); values.insert(x3, pose3 * noise_pose); // All factors are disabled and pose should remain where it is Values result; LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); result = optimizer.optimize(); EXPECT(assert_equal(values.at(x3), result.at(x3))); } /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); StereoCamera cam2(pose2, K); // create third camera 1 meter above the first camera Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); StereoCamera cam3(pose3, K); // three landmarks ~5 meters infront of camera Point3 landmark1(5, 0.5, 1.2); Point3 landmark2(5, -0.5, 1.2); Point3 landmark3(3, 0, 3.0); Point3 landmark4(5, -0.5, 1); // 1. Project four landmarks into three cameras and triangulate vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); vector measurements_cam4 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark4); measurements_cam4.at(0) = measurements_cam4.at(0) + StereoPoint2(10, 10, 1); // add outlier SmartStereoProjectionParams params; params.setLinearizationMode(JACOBIAN_SVD); params.setDynamicOutlierRejectionThreshold(1); SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(params)); smartFactor1->add(measurements_cam1, views, model, K); SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(params)); smartFactor2->add(measurements_cam2, views, model, K); SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(params)); smartFactor3->add(measurements_cam3, views, model, K); SmartStereoProjectionPoseFactor::shared_ptr smartFactor4(new SmartStereoProjectionPoseFactor(params)); smartFactor4->add(measurements_cam4, views, model, K); // same as factor 4, but dynamic outlier rejection is off SmartStereoProjectionPoseFactor::shared_ptr smartFactor4b(new SmartStereoProjectionPoseFactor()); smartFactor4b->add(measurements_cam4, views, model, K); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); graph.push_back(smartFactor4); graph.push_back(PriorFactor(x1, pose1, noisePrior)); graph.push_back(PriorFactor(x2, pose2, noisePrior)); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, pose1); values.insert(x2, pose2); values.insert(x3, pose3); EXPECT_DOUBLES_EQUAL(0, smartFactor1->error(values), 1e-9); EXPECT_DOUBLES_EQUAL(0, smartFactor2->error(values), 1e-9); EXPECT_DOUBLES_EQUAL(0, smartFactor3->error(values), 1e-9); // zero error due to dynamic outlier rejection EXPECT_DOUBLES_EQUAL(0, smartFactor4->error(values), 1e-9); // dynamic outlier rejection is off EXPECT_DOUBLES_EQUAL(6272.613220592455, smartFactor4b->error(values), 1e-9); // Factors 1-3 should have valid point, factor 4 should not EXPECT(smartFactor1->point()); EXPECT(smartFactor2->point()); EXPECT(smartFactor3->point()); EXPECT(smartFactor4->point().degenerate()); EXPECT(smartFactor4b->point()); // Factor 4 is disabled, pose 3 stays put Values result; LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); result = optimizer.optimize(); EXPECT(assert_equal(pose3, result.at(x3))); } // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, jacobianQ ){ // // vector views; // views.push_back(x1); // views.push_back(x2); // views.push_back(x3); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) // Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K); // // create second camera 1 meter to the right of first camera // Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); // StereoCamera cam2(pose2, K); // // create third camera 1 meter above the first camera // Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); // StereoCamera cam3(pose3, K); // // // three landmarks ~5 meters infront of camera // Point3 landmark1(5, 0.5, 1.2); // Point3 landmark2(5, -0.5, 1.2); // Point3 landmark3(3, 0, 3.0); // // vector measurements_cam1, measurements_cam2, measurements_cam3; // // // 1. Project three landmarks into three cameras and triangulate // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); // // SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(1, -1, false, false, JACOBIAN_Q)); // smartFactor1->add(measurements_cam1, views, model, K); // // SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(1, -1, false, false, JACOBIAN_Q)); // smartFactor2->add(measurements_cam2, views, model, K); // // SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(1, -1, false, false, JACOBIAN_Q)); // smartFactor3->add(measurements_cam3, views, model, K); // // const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); // // NonlinearFactorGraph graph; // graph.push_back(smartFactor1); // graph.push_back(smartFactor2); // graph.push_back(smartFactor3); // graph.push_back(PriorFactor(x1, pose1, noisePrior)); // graph.push_back(PriorFactor(x2, pose2, noisePrior)); // // // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), Point3(0.1,0.1,0.1)); // smaller noise // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2); // values.insert(x3, pose3*noise_pose); // //// Values result; // LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); // result = optimizer.optimize(); // EXPECT(assert_equal(pose3,result.at(x3))); //} // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, 3poses_projection_factor ){ // // vector views; // views.push_back(x1); // views.push_back(x2); // views.push_back(x3); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) // Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K2); // // // create second camera 1 meter to the right of first camera // Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); // StereoCamera cam2(pose2, K2); // // // create third camera 1 meter above the first camera // Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); // StereoCamera cam3(pose3, K2); // // // three landmarks ~5 meters infront of camera // Point3 landmark1(5, 0.5, 1.2); // Point3 landmark2(5, -0.5, 1.2); // Point3 landmark3(3, 0, 3.0); // // typedef GenericStereoFactor ProjectionFactor; // NonlinearFactorGraph graph; // // // 1. Project three landmarks into three cameras and triangulate // graph.push_back(ProjectionFactor(cam1.project(landmark1), model, x1, L(1), K2)); // graph.push_back(ProjectionFactor(cam2.project(landmark1), model, x2, L(1), K2)); // graph.push_back(ProjectionFactor(cam3.project(landmark1), model, x3, L(1), K2)); // // graph.push_back(ProjectionFactor(cam1.project(landmark2), model, x1, L(2), K2)); // graph.push_back(ProjectionFactor(cam2.project(landmark2), model, x2, L(2), K2)); // graph.push_back(ProjectionFactor(cam3.project(landmark2), model, x3, L(2), K2)); // // graph.push_back(ProjectionFactor(cam1.project(landmark3), model, x1, L(3), K2)); // graph.push_back(ProjectionFactor(cam2.project(landmark3), model, x2, L(3), K2)); // graph.push_back(ProjectionFactor(cam3.project(landmark3), model, x3, L(3), K2)); // // const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); // graph.push_back(PriorFactor(x1, pose1, noisePrior)); // graph.push_back(PriorFactor(x2, pose2, noisePrior)); // // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2); // values.insert(x3, pose3* noise_pose); // values.insert(L(1), landmark1); // values.insert(L(2), landmark2); // values.insert(L(3), landmark3); // // LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); // Values result = optimizer.optimize(); // // EXPECT(assert_equal(pose3,result.at(x3))); //} // /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); StereoCamera cam2(pose2, K); // create third camera Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); StereoCamera cam3(pose3, K); // three landmarks ~5 meters infront of camera Point3 landmark1(5, 0.5, 1.2); Point3 landmark2(5, -0.5, 1.2); Point3 landmark3(3, 0, 3.0); // Project three landmarks into three cameras and triangulate vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); SmartStereoProjectionParams params; params.setRankTolerance(10); SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(params)); smartFactor1->add(measurements_cam1, views, model, K); SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(params)); smartFactor2->add(measurements_cam2, views, model, K); SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(params)); smartFactor3->add(measurements_cam3, views, model, K); // Create graph to optimize NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); Values values; values.insert(x1, pose1); values.insert(x2, pose2); // initialize third pose with some noise, we expect it to move back to original pose3 Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise values.insert(x3, pose3 * noise_pose); // TODO: next line throws Cheirality exception on Mac boost::shared_ptr hessianFactor1 = smartFactor1->linearize( values); boost::shared_ptr hessianFactor2 = smartFactor2->linearize( values); boost::shared_ptr hessianFactor3 = smartFactor3->linearize( values); Matrix CumulativeInformation = hessianFactor1->information() + hessianFactor2->information() + hessianFactor3->information(); boost::shared_ptr GaussianGraph = graph.linearize( values); Matrix GraphInformation = GaussianGraph->hessian().first; // Check Hessian EXPECT(assert_equal(GraphInformation, CumulativeInformation, 1e-8)); Matrix AugInformationMatrix = hessianFactor1->augmentedInformation() + hessianFactor2->augmentedInformation() + hessianFactor3->augmentedInformation(); // Check Information vector Vector InfoVector = AugInformationMatrix.block(0, 18, 18, 1); // 18x18 Hessian + information vector // Check Hessian EXPECT(assert_equal(InfoVector, GaussianGraph->hessian().second, 1e-8)); } // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ){ // // vector views; // views.push_back(x1); // views.push_back(x2); // views.push_back(x3); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) // Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K2); // // // create second camera 1 meter to the right of first camera // Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); // StereoCamera cam2(pose2, K2); // // // create third camera 1 meter above the first camera // Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); // StereoCamera cam3(pose3, K2); // // // three landmarks ~5 meters infront of camera // Point3 landmark1(5, 0.5, 1.2); // Point3 landmark2(5, -0.5, 1.2); // // vector measurements_cam1, measurements_cam2, measurements_cam3; // // // 1. Project three landmarks into three cameras and triangulate // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); // // double rankTol = 50; // SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy)); // smartFactor1->add(measurements_cam1, views, model, K2); // // SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy)); // smartFactor2->add(measurements_cam2, views, model, K2); // // const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); // const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); // Point3 positionPrior = Point3(0,0,1); // // NonlinearFactorGraph graph; // graph.push_back(smartFactor1); // graph.push_back(smartFactor2); // graph.push_back(PriorFactor(x1, pose1, noisePrior)); // graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); // graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); // // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.1,0.1,0.1)); // smaller noise // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2*noise_pose); // // initialize third pose with some noise, we expect it to move back to original pose3 // values.insert(x3, pose3*noise_pose*noise_pose); // // Values result; // gttic_(SmartStereoProjectionPoseFactor); // LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); // result = optimizer.optimize(); // gttoc_(SmartStereoProjectionPoseFactor); // tictoc_finishedIteration_(); // // // result.print("results of 3 camera, 3 landmark optimization \n"); // // EXPECT(assert_equal(pose3,result.at(x3))); //} // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ){ // // vector views; // views.push_back(x1); // views.push_back(x2); // views.push_back(x3); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) // Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K); // // // create second camera 1 meter to the right of first camera // Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); // StereoCamera cam2(pose2, K); // // // create third camera 1 meter above the first camera // Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); // StereoCamera cam3(pose3, K); // // // three landmarks ~5 meters infront of camera // Point3 landmark1(5, 0.5, 1.2); // Point3 landmark2(5, -0.5, 1.2); // Point3 landmark3(3, 0, 3.0); // // vector measurements_cam1, measurements_cam2, measurements_cam3; // // // 1. Project three landmarks into three cameras and triangulate // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); // // double rankTol = 10; // // SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy)); // smartFactor1->add(measurements_cam1, views, model, K); // // SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy)); // smartFactor2->add(measurements_cam2, views, model, K); // // SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy)); // smartFactor3->add(measurements_cam3, views, model, K); // // const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); // const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); // Point3 positionPrior = Point3(0,0,1); // // NonlinearFactorGraph graph; // graph.push_back(smartFactor1); // graph.push_back(smartFactor2); // graph.push_back(smartFactor3); // graph.push_back(PriorFactor(x1, pose1, noisePrior)); // graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); // graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); // // // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), Point3(0.1,0.1,0.1)); // smaller noise // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2); // // initialize third pose with some noise, we expect it to move back to original pose3 // values.insert(x3, pose3*noise_pose); // // Values result; // gttic_(SmartStereoProjectionPoseFactor); // LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); // result = optimizer.optimize(); // gttoc_(SmartStereoProjectionPoseFactor); // tictoc_finishedIteration_(); // // // result.print("results of 3 camera, 3 landmark optimization \n"); // // EXPECT(assert_equal(pose3,result.at(x3))); //} // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, Hessian ){ // // vector views; // views.push_back(x1); // views.push_back(x2); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) // Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K2); // // // create second camera 1 meter to the right of first camera // Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); // StereoCamera cam2(pose2, K2); // // // three landmarks ~5 meters infront of camera // Point3 landmark1(5, 0.5, 1.2); // // // 1. Project three landmarks into three cameras and triangulate // StereoPoint2 cam1_uv1 = cam1.project(landmark1); // StereoPoint2 cam2_uv1 = cam2.project(landmark1); // vector measurements_cam1; // measurements_cam1.push_back(cam1_uv1); // measurements_cam1.push_back(cam2_uv1); // // SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor()); // smartFactor1->add(measurements_cam1,views, model, K2); // // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2); // // boost::shared_ptr hessianFactor = smartFactor1->linearize(values); // // // compute triangulation from linearization point // // compute reprojection errors (sum squared) // // compare with hessianFactor.info(): the bottom right element is the squared sum of the reprojection errors (normalized by the covariance) // // check that it is correctly scaled when using noiseProjection = [1/4 0; 0 1/4] //} // /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ) { vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); StereoCamera cam2(pose2, K); // create third camera 1 meter above the first camera Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); StereoCamera cam3(pose3, K); Point3 landmark1(5, 0.5, 1.2); vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); SmartStereoProjectionPoseFactor::shared_ptr smartFactorInstance(new SmartStereoProjectionPoseFactor()); smartFactorInstance->add(measurements_cam1, views, model, K); Values values; values.insert(x1, pose1); values.insert(x2, pose2); values.insert(x3, pose3); boost::shared_ptr hessianFactor = smartFactorInstance->linearize(values); // hessianFactor->print("Hessian factor \n"); Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; rotValues.insert(x1, poseDrift.compose(pose1)); rotValues.insert(x2, poseDrift.compose(pose2)); rotValues.insert(x3, poseDrift.compose(pose3)); boost::shared_ptr hessianFactorRot = smartFactorInstance->linearize(rotValues); // hessianFactorRot->print("Hessian factor \n"); // Hessian is invariant to rotations in the nondegenerate case EXPECT( assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-7)); Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); Values tranValues; tranValues.insert(x1, poseDrift2.compose(pose1)); tranValues.insert(x2, poseDrift2.compose(pose2)); tranValues.insert(x3, poseDrift2.compose(pose3)); boost::shared_ptr hessianFactorRotTran = smartFactorInstance->linearize(tranValues); // Hessian is invariant to rotations and translations in the nondegenerate case EXPECT( assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-6)); } /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K2); // Second and third cameras in same place, which is a degenerate configuration Pose3 pose2 = pose1; Pose3 pose3 = pose1; StereoCamera cam2(pose2, K2); StereoCamera cam3(pose3, K2); Point3 landmark1(5, 0.5, 1.2); vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); SmartStereoProjectionPoseFactor::shared_ptr smartFactor(new SmartStereoProjectionPoseFactor()); smartFactor->add(measurements_cam1, views, model, K2); Values values; values.insert(x1, pose1); values.insert(x2, pose2); values.insert(x3, pose3); boost::shared_ptr hessianFactor = smartFactor->linearize( values); Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; rotValues.insert(x1, poseDrift.compose(pose1)); rotValues.insert(x2, poseDrift.compose(pose2)); rotValues.insert(x3, poseDrift.compose(pose3)); boost::shared_ptr hessianFactorRot = smartFactor->linearize( rotValues); // Hessian is invariant to rotations in the nondegenerate case EXPECT( assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-7)); Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); Values tranValues; tranValues.insert(x1, poseDrift2.compose(pose1)); tranValues.insert(x2, poseDrift2.compose(pose2)); tranValues.insert(x3, poseDrift2.compose(pose3)); boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); // Hessian is invariant to rotations and translations in the nondegenerate case EXPECT( assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-6)); } /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */