sample.cpp 3.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107
  1. //
  2. // Created by zx on 23-6-20.
  3. //
  4. #include <gtsam/geometry/Pose2.h>
  5. #include <gtsam/geometry/Pose3.h>
  6. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  7. #include <gtsam/nonlinear/Values.h>
  8. #include <gtsam/inference/Symbol.h>
  9. #include <gtsam/slam/PriorFactor.h>
  10. #include <gtsam/slam/BetweenFactor.h>
  11. #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
  12. #include <gtsam/nonlinear/Marginals.h>
  13. #include <gtsam/nonlinear/ISAM2.h>
  14. #include "Edge3Factor.h"
  15. bool SolveXYZ(std::vector<gtsam::Vector3> xyzs)
  16. {
  17. if(xyzs.size()<1){
  18. printf("xyzs size must >= 1\n");
  19. return false;
  20. }
  21. using gtsam::symbol_shorthand::X;
  22. using gtsam::symbol_shorthand::Y;
  23. using gtsam::symbol_shorthand::Z;
  24. //定义图
  25. gtsam::NonlinearFactorGraph graph;
  26. gtsam::ISAM2Params parameters;
  27. parameters.relinearizeThreshold = 0.1;
  28. parameters.relinearizeSkip = 1;
  29. gtsam::ISAM2* isam=new gtsam::ISAM2(parameters);
  30. //定义待求因子
  31. const int NUM=xyzs.size();
  32. //
  33. double a=1.0;
  34. double b=1.0;
  35. double dx=0.1;
  36. double dy=0.2;
  37. double dz= sqrt(a*a*dx*dx+b*b*dy*dy)*2;
  38. double x=xyzs[0][0];
  39. double y=xyzs[0][1];
  40. double z=xyzs[0][2];
  41. gtsam::Values initials;
  42. initials.insert(X(0),x);
  43. initials.insert(Y(0),y);
  44. initials.insert(Z(0),z);
  45. for (int i=0;i<NUM;++i){
  46. double x=xyzs[i][0];
  47. double y=xyzs[i][1];
  48. double z=xyzs[i][2];
  49. printf(" prior xyz :%.5f %.5f %.5f\n",x,y,z);
  50. //先验分布
  51. Eigen::Matrix<double,1,1> sigma_x=Eigen::Matrix<double,1,1>::Ones()*dx;
  52. gtsam::noiseModel::Diagonal::shared_ptr priorModel_x = gtsam::noiseModel::Diagonal::Sigmas(sigma_x);
  53. graph.add(gtsam::PriorFactor<double>(X(0), x, priorModel_x));
  54. Eigen::Matrix<double,1,1> sigma_y=Eigen::Matrix<double,1,1>::Ones()*dy;
  55. gtsam::noiseModel::Diagonal::shared_ptr priorModel_y = gtsam::noiseModel::Diagonal::Sigmas(sigma_y);
  56. graph.add(gtsam::PriorFactor<double>(Y(0), y, priorModel_y));
  57. Eigen::Matrix<double,1,1> sigma_z=Eigen::Matrix<double,1,1>::Ones()*dz;
  58. gtsam::noiseModel::Diagonal::shared_ptr priorModel_z = gtsam::noiseModel::Diagonal::Sigmas(sigma_z);
  59. graph.add(gtsam::PriorFactor<double>(Z(0), z, priorModel_z));
  60. }
  61. for(int i=0;i<NUM;++i){
  62. Eigen::Matrix<double,2,1> sigma_ab=Eigen::Matrix<double,2,1>::Zero();
  63. sigma_ab(0,0)=0.0001;
  64. sigma_ab(1,0)=0.0001;
  65. gtsam::noiseModel::Diagonal::shared_ptr priorModel_t = gtsam::noiseModel::Diagonal::Sigmas(sigma_ab);
  66. //增加前后两点z值增量的概率分布,均值为0,方差为sigma_a的分布
  67. graph.add(Edge3Factor(X(0),Y(0),Z(0), a,b, priorModel_t));
  68. }
  69. isam->update(graph,initials);
  70. isam->update();
  71. gtsam::Values results=isam->calculateEstimate();
  72. double ox=results.at<double>(X(0));
  73. double oy=results.at<double>(Y(0));
  74. double oz=results.at<double>(Z(0));
  75. printf(" ox oy oz:%.5f %.5f %.5f error z:%.5f\n",ox,oy,oz,(a*ox+b*oy)-oz);
  76. return true;
  77. }
  78. int main(){
  79. gtsam::Pose3 poseSrc(gtsam::Rot3::RzRyRx(0,0,-3.0),
  80. gtsam::Point3(0,0,0));
  81. gtsam::Pose3 poseTar(gtsam::Rot3::RzRyRx(1,0,0),
  82. gtsam::Point3(1,0,0));
  83. gtsam::Pose3 between = poseSrc.between(poseTar);
  84. printf("between:(%f %f %f),(%f,%f,%f)\n",between.x(),between.y(),between.z(),
  85. between.rotation().roll(),between.rotation().pitch(),between.rotation().yaw());
  86. return 0;
  87. std::vector<gtsam::Vector3> xyzs;
  88. gtsam::Vector3 xyz(1,2,4);
  89. xyzs.push_back(xyz);
  90. printf(" x y z:%.5f %.5f %.5f\n",xyz[0],xyz[1],xyz[2]);
  91. SolveXYZ(xyzs);
  92. }