TransformProjectionFactorExampleISAM.m 4.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175
  1. %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
  2. % GTSAM Copyright 2010, Georgia Tech Research Corporation,
  3. % Atlanta, Georgia 30332-0415
  4. % All Rights Reserved
  5. % Authors: Frank Dellaert, et al. (see THANKS for the full author list)
  6. %
  7. % See LICENSE for the license information
  8. %
  9. % @brief Read graph from file and perform GraphSLAM
  10. % @author Frank Dellaert
  11. %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
  12. clear all;
  13. clc;
  14. import gtsam.*
  15. write_video = true;
  16. if(write_video)
  17. videoObj = VideoWriter('test.avi');
  18. videoObj.Quality = 100;
  19. videoObj.FrameRate = 2;
  20. open(videoObj);
  21. end
  22. %% generate some landmarks
  23. nrPoints = 8;
  24. landmarks = {Point3([20 15 1]'),...
  25. Point3([22 7 -1]'),...
  26. Point3([20 20 6]'),...
  27. Point3([24 19 -4]'),...
  28. Point3([26 17 -2]'),...
  29. Point3([12 15 4]'),...
  30. Point3([25 11 -6]'),...
  31. Point3([23 10 4]')};
  32. fg = NonlinearFactorGraph;
  33. pose_cov = noiseModel.Diagonal.Sigmas([1*pi/180; 1*pi/180; 1*pi/180; 0.1; 0.1; 0.1]);
  34. fg.add(PriorFactorPose3(1, Pose3(),pose_cov));
  35. fg.add(PriorFactorPose3(2, Pose3(Rot3(),Point3(1,0,0)),pose_cov));
  36. curvature = 0.5;
  37. initial = Values;
  38. %% intial landmarks and camera trajectory shifted in + y-direction
  39. y_shift = Point3(0,1,0);
  40. % insert shifted points
  41. for i=1:nrPoints
  42. initial.insert(100+i,landmarks{i} + y_shift);
  43. end
  44. figure(1);
  45. cla
  46. hold on;
  47. %% Actual camera translation coincides with odometry, but -90deg Z-X rotation
  48. camera_transform = Pose3(Rot3.RzRyRx(-pi/2, 0, -pi/2),y_shift);
  49. actual_transform = Pose3(Rot3.RzRyRx(-pi/2, 0, -pi/2),Point3());
  50. initial.insert(1000,camera_transform);
  51. trans_cov = noiseModel.Diagonal.Sigmas([5*pi/180; 5*pi/180; 5*pi/180; 20; 20; 20]);
  52. fg.add(PriorFactorPose3(1000,camera_transform,trans_cov));
  53. %% insert poses
  54. initial.insert(1, Pose3());
  55. move_forward = Pose3(Rot3(),Point3(1,0,0));
  56. move_circle = Pose3(Rot3.RzRyRx(0.0,0.0,curvature*pi/180),Point3(1,0,0));
  57. covariance = noiseModel.Diagonal.Sigmas([5*pi/180; 5*pi/180; 5*pi/180; 0.05; 0.05; 0.05]);
  58. z_cov = noiseModel.Diagonal.Sigmas([1.0;1.0]);
  59. K = Cal3_S2(900,900,0,640,480);
  60. cheirality_exception_count = 0;
  61. isamParams = gtsam.ISAM2Params;
  62. isamParams.setFactorization('QR');
  63. isam = ISAM2(isamParams);
  64. result = initial
  65. for i=1:20
  66. if i > 1
  67. if i < 11
  68. initial.insert(i,result.atPose3(i-1).compose(move_forward));
  69. fg.add(BetweenFactorPose3(i-1,i, move_forward, covariance));
  70. else
  71. initial.insert(i,result.atPose3(i-1).compose(move_circle));
  72. fg.add(BetweenFactorPose3(i-1,i, move_circle, covariance));
  73. end
  74. end
  75. % generate some camera measurements
  76. cam_pose = initial.atPose3(i).compose(actual_transform);
  77. % gtsam.plotPose3(cam_pose);
  78. cam = PinholeCameraCal3_S2(cam_pose,K);
  79. i
  80. % result
  81. for j=1:nrPoints
  82. % All landmarks seen in every frame
  83. try
  84. z = cam.project(landmarks{j});
  85. fg.add(TransformProjectionFactorCal3_S2(z, z_cov, i, 1000, 100+j, K));
  86. catch
  87. cheirality_exception_count = cheirality_exception_count + 1;
  88. end % end try/catch
  89. end
  90. if i > 2
  91. disp('ISAM Update');
  92. isam.update(fg, initial);
  93. result = isam.calculateEstimate();
  94. %% reset
  95. initial = Values;
  96. fg = NonlinearFactorGraph;
  97. end
  98. hold off;
  99. clf;
  100. hold on;
  101. %% plot results
  102. result_camera_transform = result.atPose3(1000);
  103. for j=1:i
  104. gtsam.plotPose3(result.atPose3(j));
  105. gtsam.plotPose3(result.atPose3(j).compose(result_camera_transform),[],0.5);
  106. end
  107. xlabel('x (m)');
  108. ylabel('y (m)');
  109. title(sprintf('Curvature %g deg, iteration %g', curvature, i));
  110. axis([0 20 0 20 -10 10]);
  111. view(-37,40);
  112. % axis equal
  113. for l=101:100+nrPoints
  114. plotPoint3(result.atPoint3(l),'g');
  115. end
  116. t = result.atPose3(1000).translation();
  117. ty = t(2);
  118. text(5,5,5,sprintf('Y-Transform: %0.2g',ty));
  119. if(write_video)
  120. currFrame = getframe(gcf);
  121. writeVideo(videoObj, currFrame)
  122. else
  123. pause(0.001);
  124. end
  125. end
  126. if(write_video)
  127. close(videoObj);
  128. end
  129. fprintf('Cheirality Exception count: %d\n', cheirality_exception_count);
  130. disp('Transform after optimization');
  131. result.atPose3(1000)