sample.cpp 7.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280
  1. #include <gtsam/geometry/Pose2.h>
  2. #include <gtsam/geometry/Pose3.h>
  3. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  4. #include <gtsam/nonlinear/Values.h>
  5. #include <gtsam/inference/Symbol.h>
  6. #include <gtsam/slam/PriorFactor.h>
  7. #include <gtsam/slam/BetweenFactor.h>
  8. #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
  9. #include <gtsam/nonlinear/Marginals.h>
  10. #include <gtsam/nonlinear/ISAM2.h>
  11. #include <gtsam/navigation/GPSFactor.h>
  12. #include <gtsam/slam/PoseRotationPrior.h>
  13. #include <gtsam/slam/PoseTranslationPrior.h>
  14. #include <pcl/point_types.h>
  15. #include <pcl/point_cloud.h>
  16. #include <pcl/io/pcd_io.h>
  17. #include <thread>
  18. using namespace std;
  19. using namespace gtsam;
  20. #include <opencv2/opencv.hpp>
  21. int height=500;
  22. int width=500;
  23. cv::Mat image=cv::Mat::zeros(width,height,CV_8UC3)+cv::Scalar(255,255,255);
  24. void init_image(gtsam::Values& poses,cv::Scalar color)
  25. {
  26. int size=poses.size();
  27. //poses.print("123");
  28. for(int i=0;i<size;++i)
  29. {
  30. gtsam::Pose2 pose=poses.at<Pose2>(i);
  31. int x=int(pose.x()*20+width/2);
  32. int y=int(pose.y()*20+height/2);
  33. cv::circle(image,cv::Point(x,y),3,color);
  34. }
  35. }
  36. void show_pose(gtsam::Values& poses,cv::Scalar color)
  37. {
  38. int size=poses.size();
  39. std::cout<<" result size"<<size<<std::endl;
  40. cv::Mat rgb=image.clone();
  41. for(int i=0;i<size;++i)
  42. {
  43. gtsam::Pose2 pose=poses.at<Pose2>(i);
  44. int x=int(pose.x()*20+width/2);
  45. int y=int(pose.y()*20+height/2);
  46. cv::circle(rgb,cv::Point(x,y),3,color);
  47. }
  48. cv::imshow("win",rgb);
  49. //cv::imwrite("./img.jpg",image);
  50. cv::waitKey(0);
  51. }
  52. Eigen::Quaterniond rpy_quat(const Eigen::Vector3d& rpy)
  53. {
  54. Eigen::AngleAxisd rollAngle(Eigen::AngleAxisd(rpy[0],Eigen::Vector3d::UnitX()));
  55. Eigen::AngleAxisd pitchAngle(Eigen::AngleAxisd(rpy[1],Eigen::Vector3d::UnitY()));
  56. Eigen::AngleAxisd yawAngle(Eigen::AngleAxisd(rpy[2],Eigen::Vector3d::UnitZ()));
  57. Eigen::Quaterniond quaternion;
  58. quaternion=yawAngle*pitchAngle*rollAngle;
  59. return quaternion;
  60. }
  61. Eigen::Vector3d quat_rpy(Eigen::Quaterniond quaternion)
  62. {
  63. return quaternion.matrix().eulerAngles(2,1,0);
  64. }
  65. bool string2point(std::string str,pcl::PointXYZ& point)
  66. {
  67. std::istringstream iss;
  68. iss.str(str);
  69. float value;
  70. float data[3]={0};
  71. for(int i=0;i<3;++i)
  72. {
  73. if(iss>>value)
  74. {
  75. data[i]=value;
  76. }
  77. else
  78. {
  79. return false;
  80. }
  81. }
  82. point.x=data[0]/1000.0;
  83. point.y=data[1]/1000.0;
  84. point.z=data[2]/1000.;
  85. return true;
  86. }
  87. pcl::PointCloud<pcl::PointXYZ>::Ptr ReadTxtCloud(std::string file)
  88. {
  89. std::ifstream fin(file.c_str());
  90. const int line_length=64;
  91. char str[line_length]={0};
  92. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
  93. while(fin.getline(str,line_length))
  94. {
  95. pcl::PointXYZ point;
  96. if(string2point(str,point))
  97. {
  98. cloud->push_back(point);
  99. }
  100. }
  101. return cloud;
  102. }
  103. const int THREAD_NUM=1;
  104. bool exits[THREAD_NUM]={false};
  105. std::vector<pcl::PointXYZ> line;
  106. void test_zzjj(float mean)
  107. {
  108. using gtsam::symbol_shorthand::Y; //
  109. NonlinearFactorGraph graph;
  110. gtsam::ISAM2Params parameters;
  111. parameters.relinearizeThreshold = 0.1;
  112. parameters.relinearizeSkip = 1;
  113. gtsam::ISAM2* isam=new gtsam::ISAM2(parameters);
  114. Values initials;
  115. const int NUM=line.size();
  116. /*
  117. * 定义两个sigma及高斯模型
  118. * sigma代表测量数据概率分布(可信度)
  119. * sigma_a代表前后两个点z值增量概率分布(可信度)
  120. */
  121. Eigen::Matrix<double,1,1> sigma=Eigen::Matrix<double,1,1>::Ones()*0.15;
  122. noiseModel::Diagonal::shared_ptr priorModel = noiseModel::Diagonal::Sigmas(sigma);
  123. //sigma_a=0.01 时允许优化出来的线条前后值差在 1cm左右(调节该值即调整优化曲线的平滑度)
  124. Eigen::Matrix<double,1,1> sigma_a=Eigen::Matrix<double,1,1>::Ones()*0.001;
  125. noiseModel::Diagonal::shared_ptr priorModel_a = noiseModel::Diagonal::Sigmas(sigma_a);
  126. //添加优化变量节点,赋初值为测量值
  127. for(int i=0;i<NUM;++i)
  128. {
  129. initials.insert(Y(i),line[i].z);
  130. }
  131. graph.add(PriorFactor<float>(Y(0), line[0].z, priorModel));
  132. for(int i=0;i<NUM-1;++i)
  133. {
  134. //增加测量值先验概率分布, 均值为测量值,方差为sigma_t的分布
  135. float dy=line[i+1].z-mean;
  136. //动态调整测量值的先验概率分布, 低点赋予高可信度
  137. float r=0.2/(1.0+exp(-10000.*(dy-0.001)))+0.003;
  138. Eigen::Matrix<double,1,1> sigma_t=Eigen::Matrix<double,1,1>::Ones()*r;
  139. noiseModel::Diagonal::shared_ptr priorModel_t = noiseModel::Diagonal::Sigmas(sigma_t);
  140. graph.add(PriorFactor<float>(Y(i+1), line[i+1].z, priorModel_t));
  141. //增加前后两点z值增量的概率分布,均值为0,方差为sigma_a的分布
  142. graph.add(BetweenFactor<float>(Y(i), Y(i+1), 0., priorModel_a));
  143. }
  144. isam->update(graph,initials);
  145. isam->update();
  146. gtsam::Values results=isam->calculateEstimate();
  147. //保存结果
  148. FILE* p=fopen("./line.txt","w");
  149. for(int i=0;i<line.size();++i)
  150. {
  151. pcl::PointXYZ point=line[i];
  152. fprintf(p,"%f %f %f 0 255 0\n",point.x,point.y,results.at<float>(Y(i)));
  153. if(point.z-results.at<float>(Y(i))>0.003)
  154. {
  155. fprintf(p,"%f %f %f 255 0 0\n",point.x,point.y,point.z);
  156. }
  157. else
  158. {
  159. fprintf(p,"%f %f %f 255 255 255\n",point.x,point.y,point.z);
  160. }
  161. }
  162. /*std::cout<<std::endl<<"-------------y-----------"<<std::endl;
  163. for(int i=0;i<20;++i)
  164. {
  165. printf("%.5f ",float(i)/10.0);
  166. }
  167. printf("\n");
  168. for(int i=0;i<20;++i)
  169. {
  170. printf("%.5f ",y[i]);
  171. }
  172. printf("\n");
  173. for(int i=0;i<20;++i)
  174. {
  175. double s=results.at<Point2>(Y(i)).x();
  176. if(y[i]-s>0.001)
  177. {
  178. printf("%.4f* ",s);
  179. }
  180. else
  181. {
  182. printf("%.5f ", s);
  183. }
  184. }
  185. printf("\n");
  186. */
  187. exits[0]=true;
  188. }
  189. //升序排列
  190. bool cmp(const pcl::PointXYZ& value1,const pcl::PointXYZ& value2)
  191. {
  192. return value1.x>value2.x;
  193. }
  194. int main(int argc, char** argv)
  195. {
  196. //读点云, /1000,调整单位为m
  197. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud=ReadTxtCloud("/home/zx/zzw/TESTCODE/zhjj/in_4.txt");
  198. //抽取一帧数据
  199. float sum=0;
  200. for(int i=0;i<cloud->size();++i)
  201. {
  202. pcl::PointXYZ point=cloud->points[i];
  203. if(fabs(point.y-1.100)<0.00001)
  204. {
  205. line.push_back(point);
  206. sum+=point.z;
  207. }
  208. }
  209. float mean=sum/float(line.size());
  210. printf(" line size : %d mean:%f\n",line.size(),mean);
  211. //排序
  212. std::sort(line.begin(),line.end(),cmp);
  213. //计时,等待线程完成
  214. auto t0 = std::chrono::steady_clock::now();
  215. //在线程中优化
  216. std::thread* th1=new std::thread(test_zzjj,mean);
  217. while(1)
  218. {
  219. bool quite=true;
  220. for(int i=0;i<THREAD_NUM;++i)
  221. {
  222. if(exits[i]==false)
  223. {
  224. quite = false;
  225. break;
  226. }
  227. }
  228. if(quite==true)
  229. break;
  230. usleep(1);
  231. }
  232. auto t1 = std::chrono::steady_clock::now();
  233. auto duration = std::chrono::duration_cast<std::chrono::microseconds>(t1 - t0);
  234. double time=double(duration.count()) * std::chrono::microseconds::period::num /
  235. std::chrono::microseconds::period::den;
  236. std::cout << "time : "<<time<<std::endl;
  237. printf(" completed!!!");
  238. return 0;
  239. }