got it!
							parent
							
								
									0194e3df94
								
							
						
					
					
						commit
						c1da490c2d
					
				|  | @ -366,20 +366,20 @@ TEST( SmartStereoProjectionFactorPP, noisy ) { | |||
|   DOUBLES_EQUAL(actualError1, 5381978, 1); // value freeze
 | ||||
| } | ||||
| 
 | ||||
| /* *************************************************************************
 | ||||
| /* *************************************************************************/ | ||||
| TEST( SmartStereoProjectionFactorPP, 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); | ||||
|   Pose3 w_Pose_cam1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); | ||||
|   StereoCamera cam1(w_Pose_cam1, 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); | ||||
|   Pose3 w_Pose_cam2 = w_Pose_cam1 * Pose3(Rot3(), Point3(1, 0, 0)); | ||||
|   StereoCamera cam2(w_Pose_cam2, K2); | ||||
| 
 | ||||
|   // create third camera 1 meter above the first camera
 | ||||
|   Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); | ||||
|   StereoCamera cam3(pose3, K2); | ||||
|   Pose3 w_Pose_cam3 = w_Pose_cam1 * Pose3(Rot3(), Point3(0, -1, 0)); | ||||
|   StereoCamera cam3(w_Pose_cam3, K2); | ||||
| 
 | ||||
|   // three landmarks ~5 meters infront of camera
 | ||||
|   Point3 landmark1(5, 0.5, 1.2); | ||||
|  | @ -394,116 +394,136 @@ TEST( SmartStereoProjectionFactorPP, 3poses_smart_projection_factor ) { | |||
|   vector<StereoPoint2> measurements_l3 = stereo_projectToMultipleCameras(cam1, | ||||
|       cam2, cam3, landmark3); | ||||
| 
 | ||||
|   KeyVector views; | ||||
|   views.push_back(x1); | ||||
|   views.push_back(x2); | ||||
|   views.push_back(x3); | ||||
|   KeyVector poseKeys; | ||||
|   poseKeys.push_back(x1); | ||||
|   poseKeys.push_back(x2); | ||||
|   poseKeys.push_back(x3); | ||||
| 
 | ||||
|   KeyVector extrinsicKeys; | ||||
|   extrinsicKeys.push_back(body_P_cam1_key); | ||||
|   extrinsicKeys.push_back(body_P_cam2_key); | ||||
|   extrinsicKeys.push_back(body_P_cam3_key); | ||||
| 
 | ||||
|   SmartStereoProjectionParams smart_params; | ||||
|   smart_params.triangulation.enableEPI = true; | ||||
|   SmartStereoProjectionFactorPP::shared_ptr smartFactor1(new SmartStereoProjectionFactorPP(model, smart_params)); | ||||
|   smartFactor1->add(measurements_l1, views, K2); | ||||
|   smartFactor1->add(measurements_l1, poseKeys, extrinsicKeys, K2); | ||||
| 
 | ||||
|   SmartStereoProjectionFactorPP::shared_ptr smartFactor2(new SmartStereoProjectionFactorPP(model, smart_params)); | ||||
|   smartFactor2->add(measurements_l2, views, K2); | ||||
|   smartFactor2->add(measurements_l2, poseKeys, extrinsicKeys, K2); | ||||
| 
 | ||||
|   SmartStereoProjectionFactorPP::shared_ptr smartFactor3(new SmartStereoProjectionFactorPP(model, smart_params)); | ||||
|   smartFactor3->add(measurements_l3, views, K2); | ||||
|   smartFactor3->add(measurements_l3, poseKeys, extrinsicKeys, K2); | ||||
| 
 | ||||
|   const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); | ||||
| 
 | ||||
|   // Values
 | ||||
|   Pose3 body_Pose_cam1 = Pose3(Rot3::Ypr(-M_PI, 1., 0.1),Point3(0, 1, 0)); | ||||
|   Pose3 body_Pose_cam2 = Pose3(Rot3::Ypr(-M_PI / 4, 0.1, 1.0),Point3(1, 1, 1)); | ||||
|   Pose3 body_Pose_cam3 = Pose3::identity(); | ||||
|   Pose3 w_Pose_body1 = w_Pose_cam1.compose(body_Pose_cam1.inverse()); | ||||
|   Pose3 w_Pose_body2 = w_Pose_cam2.compose(body_Pose_cam2.inverse()); | ||||
|   Pose3 w_Pose_body3 = w_Pose_cam3.compose(body_Pose_cam3.inverse()); | ||||
| 
 | ||||
|   Values values; | ||||
|   Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise
 | ||||
|   values.insert(x1, w_Pose_body1); | ||||
|   values.insert(x2, w_Pose_body2); | ||||
|   values.insert(x3, w_Pose_body3); | ||||
|   values.insert(body_P_cam1_key, body_Pose_cam1); | ||||
|   values.insert(body_P_cam2_key, body_Pose_cam2); | ||||
|   // initialize third calibration with some noise, we expect it to move back to original pose3
 | ||||
|   values.insert(body_P_cam3_key, body_Pose_cam3 * noise_pose); | ||||
| 
 | ||||
|   // Graph
 | ||||
|   NonlinearFactorGraph graph; | ||||
|   graph.push_back(smartFactor1); | ||||
|   graph.push_back(smartFactor2); | ||||
|   graph.push_back(smartFactor3); | ||||
|   graph.addPrior(x1, pose1, noisePrior); | ||||
|   graph.addPrior(x2, pose2, noisePrior); | ||||
|   graph.addPrior(x1, w_Pose_body1, noisePrior); | ||||
|   graph.addPrior(x2, w_Pose_body2, noisePrior); | ||||
|   graph.addPrior(x3, w_Pose_body3, noisePrior); | ||||
|   // we might need some prior on the calibration too
 | ||||
|   graph.addPrior(body_P_cam1_key, body_Pose_cam1, noisePrior); | ||||
|   graph.addPrior(body_P_cam2_key, body_Pose_cam2, 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<Pose3>(x3))); | ||||
|               Point3(0.1, -0.1, 1.9)), values.at<Pose3>(x3) * values.at<Pose3>(body_P_cam3_key))); | ||||
| 
 | ||||
|   //  cout << std::setprecision(10) << "\n----SmartStereoFactor graph initial error: " << graph.error(values) << endl;
 | ||||
|   EXPECT_DOUBLES_EQUAL(833953.92789459578, graph.error(values), 1e-7); // initial error
 | ||||
| 
 | ||||
|   // get triangulated landmarks from smart factors
 | ||||
|   Point3 landmark1_smart = *smartFactor1->point(); | ||||
|   Point3 landmark2_smart = *smartFactor2->point(); | ||||
|   Point3 landmark3_smart = *smartFactor3->point(); | ||||
| //  // get triangulated landmarks from smart factors
 | ||||
| //  Point3 landmark1_smart = *smartFactor1->point();
 | ||||
| //  Point3 landmark2_smart = *smartFactor2->point();
 | ||||
| //  Point3 landmark3_smart = *smartFactor3->point();
 | ||||
| //
 | ||||
| //  Values result;
 | ||||
| //  gttic_(SmartStereoProjectionFactorPP);
 | ||||
| //  LevenbergMarquardtOptimizer optimizer(graph, values, lm_params);
 | ||||
| //  result = optimizer.optimize();
 | ||||
| //  gttoc_(SmartStereoProjectionFactorPP);
 | ||||
| //  tictoc_finishedIteration_();
 | ||||
| //
 | ||||
| //  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-5);
 | ||||
| 
 | ||||
|   Values result; | ||||
|   gttic_(SmartStereoProjectionFactorPP); | ||||
|   LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); | ||||
|   result = optimizer.optimize(); | ||||
|   gttoc_(SmartStereoProjectionFactorPP); | ||||
|   tictoc_finishedIteration_(); | ||||
| 
 | ||||
|   EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-5); | ||||
| 
 | ||||
| //  cout << std::setprecision(10) << "SmartStereoFactor graph optimized error: " << graph.error(result) << endl;
 | ||||
| 
 | ||||
|   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<Pose3>(x3))); | ||||
| 
 | ||||
|   // ***************************************************************
 | ||||
|   // Same problem with regular Stereo factors, expect same error!
 | ||||
|   // ****************************************************************
 | ||||
| 
 | ||||
| //  landmark1_smart.print("landmark1_smart");
 | ||||
| //  landmark2_smart.print("landmark2_smart");
 | ||||
| //  landmark3_smart.print("landmark3_smart");
 | ||||
| 
 | ||||
|   // add landmarks to values
 | ||||
|   values.insert(L(1), landmark1_smart); | ||||
|   values.insert(L(2), landmark2_smart); | ||||
|   values.insert(L(3), landmark3_smart); | ||||
| 
 | ||||
|   // add factors
 | ||||
|   NonlinearFactorGraph graph2; | ||||
| 
 | ||||
|   graph2.addPrior(x1, pose1, noisePrior); | ||||
|   graph2.addPrior(x2, pose2, noisePrior); | ||||
| 
 | ||||
|   typedef GenericStereoFactor<Pose3, Point3> ProjectionFactor; | ||||
| 
 | ||||
|   bool verboseCheirality = true; | ||||
| 
 | ||||
|   graph2.push_back(ProjectionFactor(measurements_l1[0], model, x1, L(1), K2, false, verboseCheirality)); | ||||
|   graph2.push_back(ProjectionFactor(measurements_l1[1], model, x2, L(1), K2, false, verboseCheirality)); | ||||
|   graph2.push_back(ProjectionFactor(measurements_l1[2], model, x3, L(1), K2, false, verboseCheirality)); | ||||
| 
 | ||||
|   graph2.push_back(ProjectionFactor(measurements_l2[0], model, x1, L(2), K2, false, verboseCheirality)); | ||||
|   graph2.push_back(ProjectionFactor(measurements_l2[1], model, x2, L(2), K2, false, verboseCheirality)); | ||||
|   graph2.push_back(ProjectionFactor(measurements_l2[2], model, x3, L(2), K2, false, verboseCheirality)); | ||||
| 
 | ||||
|   graph2.push_back(ProjectionFactor(measurements_l3[0], model, x1, L(3), K2, false, verboseCheirality)); | ||||
|   graph2.push_back(ProjectionFactor(measurements_l3[1], model, x2, L(3), K2, false, verboseCheirality)); | ||||
|   graph2.push_back(ProjectionFactor(measurements_l3[2], model, x3, L(3), K2, false, verboseCheirality)); | ||||
| 
 | ||||
| //  cout << std::setprecision(10) << "\n----StereoFactor graph initial error: " << graph2.error(values) << endl;
 | ||||
|   EXPECT_DOUBLES_EQUAL(833953.92789459578, graph2.error(values), 1e-7); | ||||
| 
 | ||||
|   LevenbergMarquardtOptimizer optimizer2(graph2, values, lm_params); | ||||
|   Values result2 = optimizer2.optimize(); | ||||
|   EXPECT_DOUBLES_EQUAL(0, graph2.error(result2), 1e-5); | ||||
| 
 | ||||
| //  cout << std::setprecision(10) << "StereoFactor graph optimized error: " << graph2.error(result2) << endl;
 | ||||
| ////  cout << std::setprecision(10) << "SmartStereoFactor graph optimized error: " << graph.error(result) << endl;
 | ||||
| //
 | ||||
| //  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(w_Pose_cam3, result.at<Pose3>(x3)));
 | ||||
| //
 | ||||
| //  // ***************************************************************
 | ||||
| //  // Same problem with regular Stereo factors, expect same error!
 | ||||
| //  // ****************************************************************
 | ||||
| //
 | ||||
| ////  landmark1_smart.print("landmark1_smart");
 | ||||
| ////  landmark2_smart.print("landmark2_smart");
 | ||||
| ////  landmark3_smart.print("landmark3_smart");
 | ||||
| //
 | ||||
| //  // add landmarks to values
 | ||||
| //  values.insert(L(1), landmark1_smart);
 | ||||
| //  values.insert(L(2), landmark2_smart);
 | ||||
| //  values.insert(L(3), landmark3_smart);
 | ||||
| //
 | ||||
| //  // add factors
 | ||||
| //  NonlinearFactorGraph graph2;
 | ||||
| //
 | ||||
| //  graph2.addPrior(x1, w_Pose_cam1, noisePrior);
 | ||||
| //  graph2.addPrior(x2, w_Pose_cam2, noisePrior);
 | ||||
| //
 | ||||
| //  typedef GenericStereoFactor<Pose3, Point3> ProjectionFactor;
 | ||||
| //
 | ||||
| //  bool verboseCheirality = true;
 | ||||
| //
 | ||||
| //  graph2.push_back(ProjectionFactor(measurements_l1[0], model, x1, L(1), K2, false, verboseCheirality));
 | ||||
| //  graph2.push_back(ProjectionFactor(measurements_l1[1], model, x2, L(1), K2, false, verboseCheirality));
 | ||||
| //  graph2.push_back(ProjectionFactor(measurements_l1[2], model, x3, L(1), K2, false, verboseCheirality));
 | ||||
| //
 | ||||
| //  graph2.push_back(ProjectionFactor(measurements_l2[0], model, x1, L(2), K2, false, verboseCheirality));
 | ||||
| //  graph2.push_back(ProjectionFactor(measurements_l2[1], model, x2, L(2), K2, false, verboseCheirality));
 | ||||
| //  graph2.push_back(ProjectionFactor(measurements_l2[2], model, x3, L(2), K2, false, verboseCheirality));
 | ||||
| //
 | ||||
| //  graph2.push_back(ProjectionFactor(measurements_l3[0], model, x1, L(3), K2, false, verboseCheirality));
 | ||||
| //  graph2.push_back(ProjectionFactor(measurements_l3[1], model, x2, L(3), K2, false, verboseCheirality));
 | ||||
| //  graph2.push_back(ProjectionFactor(measurements_l3[2], model, x3, L(3), K2, false, verboseCheirality));
 | ||||
| //
 | ||||
| ////  cout << std::setprecision(10) << "\n----StereoFactor graph initial error: " << graph2.error(values) << endl;
 | ||||
| //  EXPECT_DOUBLES_EQUAL(833953.92789459578, graph2.error(values), 1e-7);
 | ||||
| //
 | ||||
| //  LevenbergMarquardtOptimizer optimizer2(graph2, values, lm_params);
 | ||||
| //  Values result2 = optimizer2.optimize();
 | ||||
| //  EXPECT_DOUBLES_EQUAL(0, graph2.error(result2), 1e-5);
 | ||||
| //
 | ||||
| ////  cout << std::setprecision(10) << "StereoFactor graph optimized error: " << graph2.error(result2) << endl;
 | ||||
| 
 | ||||
| } | ||||
| /* *************************************************************************
 | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue