sample.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374
  1. //
  2. // Created by zx on 23-6-15.
  3. //
  4. #include "trajectory.h"
  5. #include <gtsam/geometry/Pose2.h>
  6. #include <gtsam/geometry/Pose3.h>
  7. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  8. #include <gtsam/nonlinear/Values.h>
  9. #include <gtsam/inference/Symbol.h>
  10. #include <gtsam/slam/PriorFactor.h>
  11. #include <gtsam/slam/BetweenFactor.h>
  12. #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
  13. #include <gtsam/nonlinear/Marginals.h>
  14. #include <gtsam/nonlinear/ISAM2.h>
  15. #include "PoseSpeedFactor.h"
  16. /*
  17. * 根据参考点生成轨迹
  18. */
  19. Trajectory update_traj(Trajectory traj,std::vector<gtsam::Vector2> speeds,int referenceId,double dt,double& loss){
  20. Trajectory ret=traj;
  21. if(referenceId>=traj.size() || referenceId<0)
  22. {
  23. printf(" reference < traj.size or referece <0 \n");
  24. return ret;
  25. }
  26. Pose2d refer=traj[referenceId];
  27. loss=0;
  28. for(int i=referenceId-1;i>=0;i--){
  29. double v=speeds[i][0];
  30. double w=speeds[i][1];
  31. double dyaw = w * dt;
  32. double theta=refer.theta()-dyaw;
  33. double dx = v * dt * cos(theta);
  34. double dy = v * dt * sin(theta);
  35. ret[i]=refer-Pose2d(dx,dy,dyaw);
  36. refer=ret[i];
  37. loss+=Pose2d::distance(ret[i],traj[i]);
  38. }
  39. refer=traj[referenceId];
  40. for(int i=referenceId+1;i<traj.size();++i){
  41. double v=speeds[i-1][0];
  42. double w=speeds[i-1][1];
  43. double dyaw = w * dt;
  44. double theta=refer.theta();
  45. double dx = v * dt * cos(theta);
  46. double dy = v * dt * sin(theta);
  47. ret[i]=refer+Pose2d(dx,dy,dyaw);
  48. refer=ret[i];
  49. loss+=Pose2d::distance(ret[i],traj[i]);
  50. }
  51. return ret;
  52. }
  53. bool SolveSpeed(Trajectory traj)
  54. {
  55. if(traj.size()<2){
  56. printf("traj size must > 2\n");
  57. return false;
  58. }
  59. using gtsam::symbol_shorthand::V;
  60. //定义图
  61. gtsam::NonlinearFactorGraph graph;
  62. gtsam::ISAM2Params parameters;
  63. parameters.relinearizeThreshold = 0.1;
  64. parameters.relinearizeSkip = 1;
  65. gtsam::ISAM2* isam=new gtsam::ISAM2(parameters);
  66. //定义待求因子
  67. const int NUM=traj.size();
  68. double dt=0.1;
  69. //
  70. double sigma_x=0.005;
  71. double sigma_yaw=0.3*M_PI/180.0;
  72. gtsam::Values initials;
  73. for (int i=0;i<NUM-1;++i){
  74. //定义变量,计算初值
  75. Pose2d relative=Pose2d::relativePose(traj[i+1],traj[i]);
  76. double v=relative.x()/dt;
  77. double w=relative.theta()/dt;
  78. gtsam::Vector2 speed;
  79. speed<<v,w;
  80. initials.insert(V(i),speed);
  81. //初值分布
  82. Eigen::Matrix<double,2,1> sigma=Eigen::Matrix<double,2,1>::Zero();
  83. sigma(0,0)=sigma_x/dt;
  84. sigma(1,0)=sigma_yaw/dt;
  85. gtsam::noiseModel::Diagonal::shared_ptr priorModel = gtsam::noiseModel::Diagonal::Sigmas(sigma);
  86. graph.add(gtsam::PriorFactor<gtsam::Vector2>(V(i), speed, priorModel));
  87. }
  88. for(int i=0;i<NUM-2;++i){
  89. Eigen::Matrix<double,2,1> sigma_acc=Eigen::Matrix<double,2,1>::Zero();
  90. sigma_acc(0,0)=1*dt;
  91. sigma_acc(1,0)=10*M_PI/180.0*dt;
  92. gtsam::noiseModel::Diagonal::shared_ptr priorModel_t = gtsam::noiseModel::Diagonal::Sigmas(sigma_acc);
  93. //增加前后两点z值增量的概率分布,均值为0,方差为sigma_a的分布
  94. graph.add(gtsam::BetweenFactor<gtsam::Vector2>(V(i), V(i+1), gtsam::Vector2(0,0), priorModel_t));
  95. }
  96. isam->update(graph,initials);
  97. isam->update();
  98. gtsam::Values results=isam->calculateEstimate();
  99. std::vector<gtsam::Vector2> speeds;
  100. for(int i=0;i<NUM-1;++i){
  101. speeds.push_back(results.at<gtsam::Vector2>(V(i)));
  102. }
  103. double min_loss=1e16;
  104. int bestId=0;
  105. Trajectory best_traj=update_traj(traj,speeds,bestId,dt,min_loss);
  106. for(int i=1;i<traj.size();++i){
  107. double loss=0;
  108. Trajectory newTraj= update_traj(traj,speeds,i,dt,loss);
  109. if(loss<min_loss){
  110. min_loss=loss;
  111. best_traj=newTraj;
  112. bestId=i;
  113. }
  114. }
  115. printf(" best traj referId:%d P:%.5f %.5f %.5f , loss:%f\n",bestId,
  116. traj[bestId].x(),traj[bestId].y(),traj[bestId].theta(),min_loss);
  117. Pose2d diff=best_traj[0] - traj[0];
  118. printf("00 P:%.4f %.4f %.4f, OPT:%.4f %.4f %.4f, Diff:%.4f %.4f %.4f, Speed:%.4f %.4f\n",
  119. traj[0].x(),traj[0].y(),traj[0].theta(),best_traj[0].x(),best_traj[0].y(),best_traj[0].theta(),
  120. diff.x(),diff.y(),diff.theta(),results.at<gtsam::Vector2>(V(0))[0],results.at<gtsam::Vector2>(V(0))[1]*180/M_PI);
  121. for(int i=1;i<NUM;++i){
  122. diff=best_traj[i] - traj[i];
  123. if(i<NUM-1) {
  124. gtsam::Vector2 Speed=results.at<gtsam::Vector2>(V(i));
  125. printf("%02d P:%.4f %.4f %.4f, OPT:%.4f %.4f %.4f, Diff:%.4f %.4f %.4f, Speed:%.4f %.4f\n",i,
  126. traj[i].x(),traj[i].y(),traj[i].theta(),best_traj[i].x(),best_traj[i].y(),best_traj[i].theta(),
  127. diff.x(),diff.y(),diff.theta(),Speed[0],Speed[1]*180/M_PI);
  128. }else{
  129. printf("%02d P:%.4f %.4f %.4f, OPT:%.4f %.4f %.4f, Diff:%.4f %.4f %.4f\n",i,
  130. traj[i].x(),traj[i].y(),traj[i].theta(),best_traj[i].x(),best_traj[i].y(),best_traj[i].theta(),
  131. diff.x(),diff.y(),diff.theta());
  132. }
  133. }
  134. return true;
  135. }
  136. bool SolvePoses(Trajectory traj){
  137. if(traj.size()<2){
  138. printf("traj size must > 2\n");
  139. return false;
  140. }
  141. using gtsam::symbol_shorthand::P;
  142. //定义图
  143. gtsam::NonlinearFactorGraph graph;
  144. gtsam::ISAM2Params parameters;
  145. parameters.relinearizeThreshold = 0.1;
  146. parameters.relinearizeSkip = 1;
  147. gtsam::ISAM2* isam=new gtsam::ISAM2(parameters);
  148. //定义待求因子
  149. const int NUM=traj.size();
  150. double dt=0.1;
  151. //
  152. double sigma_x=0.005;
  153. double sigma_y=sigma_x;
  154. double sigma_yaw=0.3*M_PI/180.0;
  155. gtsam::Values initials;
  156. for (int i=0;i<NUM;++i){
  157. //定义变量,计算初值
  158. gtsam::Pose2 pose(traj[i].x(),traj[i].y(),traj[i].theta());
  159. initials.insert(P(i),pose);
  160. //初值分布
  161. Eigen::Matrix<double,3,1> sigma=Eigen::Matrix<double,3,1>::Zero();
  162. sigma(0,0)=sigma_x;
  163. sigma(1,0)=sigma_y;
  164. sigma(2,0)=sigma_yaw;
  165. gtsam::noiseModel::Diagonal::shared_ptr priorModel = gtsam::noiseModel::Diagonal::Sigmas(sigma);
  166. graph.add(gtsam::PriorFactor<gtsam::Pose2>(P(i), pose, priorModel));
  167. //增加速度约束及分布
  168. if(i>=1){
  169. Pose2d relative=Pose2d::relativePose(traj[i],traj[i-1]);
  170. double v=sqrt(relative.x()*relative.x()+relative.y()*relative.y())/dt;
  171. if(relative.x()<0) v=-v;
  172. double w=relative.theta()/dt;
  173. gtsam::Pose2 distance(v*dt*cos(traj[i-1].theta()),v*dt*sin(traj[i-1].theta()),w*dt);
  174. Eigen::Matrix<double,3,1> sigma_distance=Eigen::Matrix<double,3,1>::Zero();
  175. sigma_distance(0,0)=sqrt(2)*sigma_x;
  176. sigma_distance(1,0)=sqrt(2)*sigma_y;
  177. sigma_distance(2,0)=sqrt(2)*sigma_yaw;
  178. gtsam::noiseModel::Diagonal::shared_ptr priorModel_t = gtsam::noiseModel::Diagonal::Sigmas(sigma_distance);
  179. graph.add(gtsam::BetweenFactor<gtsam::Pose2>(P(i-1), P(i), distance, priorModel_t));
  180. }
  181. }
  182. isam->update(graph,initials);
  183. isam->update();
  184. gtsam::Values results=isam->calculateEstimate();
  185. for(int i=0;i<NUM;++i){
  186. gtsam::Pose2 optpose=results.at<gtsam::Pose2>(P(i));
  187. Pose2d last(optpose.x(),optpose.y(),optpose.theta());
  188. Pose2d diff=last-traj[i];
  189. if(i<NUM-1) {
  190. gtsam::Pose2 pose1=results.at<gtsam::Pose2>(P(i+1));
  191. Pose2d next(pose1.x(),pose1.y(),pose1.theta());
  192. Pose2d relative=Pose2d::relativePose(next,last);
  193. double v=sqrt(relative.x()*relative.x()+relative.y()*relative.y())/dt;
  194. if(relative.x()<0) v=-v;
  195. double w=relative.theta()/dt;
  196. printf("%02d P:%.4f %.4f %.4f, OPT:%.4f %.4f %.4f, Diff:%.4f %.4f %.4f, Speed:%.4f %.4f\n",i,
  197. traj[i].x(),traj[i].y(),traj[i].theta(),optpose.x(),optpose.y(),optpose.theta(),
  198. diff.x(),diff.y(),diff.theta(),v,w*180.0/M_PI);
  199. }else{
  200. printf("%02d P:%.4f %.4f %.4f, OPT:%.4f %.4f %.4f, Diff:%.4f %.4f %.4f\n",i,
  201. traj[i].x(),traj[i].y(),traj[i].theta(),optpose.x(),optpose.y(),optpose.theta(),
  202. diff.x(),diff.y(),diff.theta());
  203. }
  204. }
  205. return true;
  206. }
  207. bool SolvePoseSpeed(Trajectory traj){
  208. if(traj.size()<2){
  209. printf("traj size must > 2\n");
  210. return false;
  211. }
  212. using gtsam::symbol_shorthand::P;
  213. using gtsam::symbol_shorthand::V;
  214. //定义图
  215. gtsam::NonlinearFactorGraph graph;
  216. gtsam::ISAM2Params parameters;
  217. parameters.relinearizeThreshold = 0.1;
  218. parameters.relinearizeSkip = 1;
  219. gtsam::ISAM2* isam=new gtsam::ISAM2(parameters);
  220. //定义待求因子
  221. const int NUM=traj.size();
  222. double dt=0.1;
  223. //
  224. double sigma_x=0.01;
  225. double sigma_y=sigma_x;
  226. double sigma_yaw=0.3*M_PI/180.0;
  227. gtsam::Values initials;
  228. for (int i=0;i<NUM;++i){
  229. //定义变量,计算初值
  230. gtsam::Pose2 pose(traj[i].x(),traj[i].y(),traj[i].theta());
  231. initials.insert(P(i),pose);
  232. //初值分布
  233. Eigen::Matrix<double,3,1> sigma=Eigen::Matrix<double,3,1>::Zero();
  234. sigma(0,0)=sigma_x;
  235. sigma(1,0)=sigma_y;
  236. sigma(2,0)=sigma_yaw;
  237. gtsam::noiseModel::Diagonal::shared_ptr priorModel = gtsam::noiseModel::Diagonal::Sigmas(sigma);
  238. graph.add(gtsam::PriorFactor<gtsam::Pose2>(P(i), pose, priorModel));
  239. if(i<NUM-1) {
  240. //增加速度分布
  241. Pose2d relative = Pose2d::relativePose(traj[i+1], traj[i]);
  242. double v = sqrt(relative.x() * relative.x() + relative.y() * relative.y()) / dt;
  243. if (relative.x() < 0) v = -v;
  244. double w = relative.theta() / dt;
  245. initials.insert(V(i), gtsam::Vector2(v, w));
  246. Eigen::Matrix<double, 2, 1> sigma_v = Eigen::Matrix<double, 2, 1>::Zero();
  247. sigma_v(0, 0) = 1.0;
  248. sigma_v(1, 0) = 10*M_PI/180.0;
  249. gtsam::noiseModel::Diagonal::shared_ptr priorModel_v = gtsam::noiseModel::Diagonal::Sigmas(sigma_v);
  250. graph.add(gtsam::PriorFactor<gtsam::Vector2>(V(i), Vector2(v,w), priorModel_v));
  251. }
  252. }
  253. for(int i=0;i<NUM-1;++i) {
  254. if(i<NUM-2) {
  255. Eigen::Matrix<double, 2, 1> sigma_a = Eigen::Matrix<double, 2, 1>::Zero();
  256. sigma_a(0, 0) = 1;
  257. sigma_a(1, 0) = 20 * M_PI / 180.0;
  258. gtsam::noiseModel::Diagonal::shared_ptr priorModel_a = gtsam::noiseModel::Diagonal::Sigmas(sigma_a);
  259. graph.add(gtsam::BetweenFactor<gtsam::Vector2>(V(i), V(i + 1), Vector2(0, 0), priorModel_a));
  260. }
  261. Eigen::Matrix<double, 3, 1> sigma_dt = Eigen::Matrix<double, 3, 1>::Ones()*0.005;
  262. gtsam::noiseModel::Diagonal::shared_ptr priorModel_dt = gtsam::noiseModel::Diagonal::Sigmas(sigma_dt);
  263. graph.add(PoseSpeedFactor(P(i), V(i),P(i+1), gtsam::Vector3(dt,dt,dt), priorModel_dt));
  264. }
  265. isam->update(graph,initials);
  266. isam->update();
  267. gtsam::Values results=isam->calculateEstimate();
  268. printf(" solve --completed--- \n");
  269. for(int i=0;i<NUM;++i){
  270. gtsam::Pose2 optpose=results.at<gtsam::Pose2>(P(i));
  271. Pose2d last(optpose.x(),optpose.y(),optpose.theta());
  272. Pose2d diff=last-traj[i];
  273. if(i<NUM-1) {
  274. gtsam::Vector2 speed=results.at<gtsam::Vector2>(V(i));
  275. printf("%02d P:%.4f %.4f %.4f, OPT:%.4f %.4f %.4f, Diff:%.4f %.4f %.4f, Speed:%.4f %.4f\n",i,
  276. traj[i].x(),traj[i].y(),traj[i].theta(),optpose.x(),optpose.y(),optpose.theta(),
  277. diff.x(),diff.y(),diff.theta(),speed[0],speed[1]*180.0/M_PI);
  278. }else{
  279. printf("%02d P:%.4f %.4f %.4f, OPT:%.4f %.4f %.4f, Diff:%.4f %.4f %.4f\n",i,
  280. traj[i].x(),traj[i].y(),traj[i].theta(),optpose.x(),optpose.y(),optpose.theta(),
  281. diff.x(),diff.y(),diff.theta());
  282. }
  283. }
  284. return true;
  285. }
  286. int main(){
  287. Trajectory traj;
  288. traj.push_point(Pose2d(0.005,0,1.565));
  289. traj.push_point(Pose2d(0.001,0.01,1.581));
  290. traj.push_point(Pose2d(0.002,0.03,1.572));
  291. traj.push_point(Pose2d(0.010,0.09,1.573));
  292. traj.push_point(Pose2d(0.009,0.2,1.571));
  293. traj.push_point(Pose2d(0.0,0.305,1.571));
  294. traj.push_point(Pose2d(0.02,0.303,1.570));
  295. traj.push_point(Pose2d(0.019,0.303,1.571));
  296. /* traj.push_point(Pose2d(0,0.4,1.57));
  297. traj.push_point(Pose2d(0,0.45,1.57));
  298. traj.push_point(Pose2d(0,0.47,1.565));
  299. traj.push_point(Pose2d(0,0.5,1.571));
  300. traj.push_point(Pose2d(0,0.51,1.571));
  301. traj.push_point(Pose2d(0,0.508,1.572));
  302. traj.push_point(Pose2d(0,0.495,1.574));
  303. traj.push_point(Pose2d(0,0.499,1.565));
  304. traj.push_point(Pose2d(0,0.501,1.568));
  305. traj.push_point(Pose2d(0,0.50,1.57));
  306. traj.push_point(Pose2d(0.005,0.501,1.57));
  307. traj.push_point(Pose2d(0.004,0.499,1.57));
  308. traj.push_point(Pose2d(-0.002,0.498,1.57));
  309. traj.push_point(Pose2d(-0.002,0.502,1.57));
  310. traj.push_point(Pose2d(-0.001,0.501,1.57));
  311. traj.push_point(Pose2d(0,0.499,1.57));*/
  312. //SolvePoses(traj);
  313. printf("-------------------------------------------------\n");
  314. auto tp=std::chrono::steady_clock::now();
  315. //SolveSpeed(traj);
  316. SolvePoseSpeed(traj);
  317. auto now=std::chrono::steady_clock::now();
  318. auto duration = std::chrono::duration_cast<std::chrono::microseconds>(now - tp);
  319. double time = double(duration.count()) * std::chrono::microseconds::period::num /
  320. std::chrono::microseconds::period::den;
  321. printf("time :%.5f s\n",time);
  322. return 0;
  323. }