ndt_matching.cpp 58 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836
  1. /*
  2. * Copyright 2015-2019 Autoware Foundation. All rights reserved.
  3. *
  4. * Licensed under the Apache License, Version 2.0 (the "License");
  5. * you may not use this file except in compliance with the License.
  6. * You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. *
  10. * Unless required by applicable law or agreed to in writing, software
  11. * distributed under the License is distributed on an "AS IS" BASIS,
  12. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. * See the License for the specific language governing permissions and
  14. * limitations under the License.
  15. */
  16. /*
  17. Localization program using Normal Distributions Transform
  18. Yuki KITSUKAWA
  19. */
  20. #include <pthread.h>
  21. #include <chrono>
  22. #include <fstream>
  23. #include <iostream>
  24. #include <memory>
  25. #include <sstream>
  26. #include <string>
  27. #include <thread>
  28. #include <boost/filesystem.hpp>
  29. #include <tf/tf.h>
  30. #include <tf/transform_broadcaster.h>
  31. #include <tf/transform_datatypes.h>
  32. #include <tf/transform_listener.h>
  33. #include <pcl/io/io.h>
  34. #include <pcl/io/pcd_io.h>
  35. #include <pcl/point_types.h>
  36. #include <pcl_conversions/pcl_conversions.h>
  37. //#include <ndt_cpu/NormalDistributionsTransform.h>
  38. #include <pcl/registration/ndt.h>
  39. #include <QFile>
  40. #include <ndt_gpu/NormalDistributionsTransform.h>
  41. #include "ndtpos.pb.h"
  42. #include "ndtgpspos.pb.h"
  43. #ifdef USE_PCL_OPENMP
  44. #include <pcl_omp_registration/ndt.h>
  45. #endif
  46. #include <pcl_ros/point_cloud.h>
  47. #include <pcl_ros/transforms.h>
  48. #include "ndt_matching.h"
  49. #include "modulecomm.h"
  50. #include "gnss_coordinate_convert.h"
  51. //the following are UBUNTU/LINUX ONLY terminal color codes.
  52. #define RESET "\033[0m"
  53. #define BLACK "\033[30m" /* Black */
  54. #define RED "\033[31m" /* Red */
  55. #define GREEN "\033[32m" /* Green */
  56. #define YELLOW "\033[33m" /* Yellow */
  57. #define BLUE "\033[34m" /* Blue */
  58. #define MAGENTA "\033[35m" /* Magenta */
  59. #define CYAN "\033[36m" /* Cyan */
  60. #define WHITE "\033[37m" /* White */
  61. #define BOLDBLACK "\033[1m\033[30m" /* Bold Black */
  62. #define BOLDRED "\033[1m\033[31m" /* Bold Red */
  63. #define BOLDGREEN "\033[1m\033[32m" /* Bold Green */
  64. #define BOLDYELLOW "\033[1m\033[33m" /* Bold Yellow */
  65. #define BOLDBLUE "\033[1m\033[34m" /* Bold Blue */
  66. #define BOLDMAGENTA "\033[1m\033[35m" /* Bold Magenta */
  67. #define BOLDCYAN "\033[1m\033[36m" /* Bold Cyan */
  68. #define BOLDWHITE "\033[1m\033[37m" /* Bold White */
  69. #define PREDICT_POSE_THRESHOLD 0.5
  70. #define Wa 0.4
  71. #define Wb 0.3
  72. #define Wc 0.3
  73. #include "ivfault.h"
  74. #include "ivlog.h"
  75. extern iv::Ivfault *gfault ;
  76. extern iv::Ivlog *givlog;
  77. static int gindex = 0;
  78. iv::lidar_pose glidar_pose;
  79. void * gpset;
  80. void * gppose;
  81. static bool g_hasmap = false;
  82. enum class MethodType
  83. {
  84. PCL_GENERIC = 0,
  85. PCL_ANH = 1,
  86. PCL_ANH_GPU = 2,
  87. PCL_OPENMP = 3,
  88. };
  89. static MethodType _method_type = MethodType::PCL_GENERIC;
  90. static pose initial_pose, predict_pose, predict_pose_imu, predict_pose_odom, predict_pose_imu_odom, previous_pose,
  91. ndt_pose, current_pose, current_pose_imu, current_pose_odom, current_pose_imu_odom, localizer_pose;
  92. static double offset_x, offset_y, offset_z, offset_yaw; // current_pos - previous_pose
  93. static double offset_imu_x, offset_imu_y, offset_imu_z, offset_imu_roll, offset_imu_pitch, offset_imu_yaw;
  94. static double offset_odom_x, offset_odom_y, offset_odom_z, offset_odom_roll, offset_odom_pitch, offset_odom_yaw;
  95. static double offset_imu_odom_x, offset_imu_odom_y, offset_imu_odom_z, offset_imu_odom_roll, offset_imu_odom_pitch,
  96. offset_imu_odom_yaw;
  97. // Can't load if typed "pcl::PointCloud<pcl::PointXYZRGB> map, add;"
  98. static pcl::PointCloud<pcl::PointXYZ> map, add;
  99. // If the map is loaded, map_loaded will be 1.
  100. static int map_loaded = 0;
  101. static int _use_gnss = 1;
  102. static int init_pos_set = 0;
  103. static pcl::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> ndt;
  104. //static cpu::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> anh_ndt;
  105. #ifdef CUDA_FOUND
  106. static std::shared_ptr<gpu::GNormalDistributionsTransform> anh_gpu_ndt_ptr =
  107. std::make_shared<gpu::GNormalDistributionsTransform>();
  108. #endif
  109. #ifdef USE_PCL_OPENMP
  110. static pcl_omp::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> omp_ndt;
  111. #endif
  112. // Default values
  113. static int max_iter = 30; // Maximum iterations
  114. static float ndt_res = 1.0; // Resolution
  115. static double step_size = 0.1; // Step size
  116. static double trans_eps = 0.01; // Transformation epsilon
  117. static double exe_time = 0.0;
  118. static bool has_converged;
  119. static int iteration = 0;
  120. static double fitness_score = 0.0;
  121. static double trans_probability = 0.0;
  122. static double diff = 0.0;
  123. static double diff_x = 0.0, diff_y = 0.0, diff_z = 0.0, diff_yaw;
  124. static double current_velocity = 0.0, previous_velocity = 0.0, previous_previous_velocity = 0.0; // [m/s]
  125. static double current_velocity_x = 0.0, previous_velocity_x = 0.0;
  126. static double current_velocity_y = 0.0, previous_velocity_y = 0.0;
  127. static double current_velocity_z = 0.0, previous_velocity_z = 0.0;
  128. // static double current_velocity_yaw = 0.0, previous_velocity_yaw = 0.0;
  129. static double current_velocity_smooth = 0.0;
  130. static double current_velocity_imu_x = 0.0;
  131. static double current_velocity_imu_y = 0.0;
  132. static double current_velocity_imu_z = 0.0;
  133. static double current_accel = 0.0, previous_accel = 0.0; // [m/s^2]
  134. static double current_accel_x = 0.0;
  135. static double current_accel_y = 0.0;
  136. static double current_accel_z = 0.0;
  137. // static double current_accel_yaw = 0.0;
  138. static double angular_velocity = 0.0;
  139. static int use_predict_pose = 0;
  140. static std::chrono::time_point<std::chrono::system_clock> matching_start, matching_end;
  141. static int _queue_size = 1000;
  142. static double predict_pose_error = 0.0;
  143. static double _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw;
  144. static Eigen::Matrix4f tf_btol;
  145. static std::string _localizer = "velodyne";
  146. static std::string _offset = "linear"; // linear, zero, quadratic
  147. static bool _get_height = false;
  148. static bool _use_local_transform = false;
  149. static bool _use_imu = false;
  150. static bool _use_odom = false;
  151. static bool _imu_upside_down = false;
  152. static bool _output_log_data = false;
  153. static std::string _imu_topic = "/imu_raw";
  154. static std::ofstream ofs;
  155. static std::string filename;
  156. //static sensor_msgs::Imu imu;
  157. //static nav_msgs::Odometry odom;
  158. // static tf::TransformListener local_transform_listener;
  159. static tf::StampedTransform local_transform;
  160. static unsigned int points_map_num = 0;
  161. pthread_mutex_t mutex;
  162. pthread_mutex_t mutex_read;
  163. pthread_mutex_t mutex_pose;
  164. bool gbNeedGPSUpdateNDT = false;
  165. pcl::PointCloud<pcl::PointXYZ>::Ptr local_map_ptr;
  166. pcl::PointCloud<pcl::PointXYZ>::Ptr global_map_ptr;
  167. pose glastmappose;
  168. static double imu_angular_velocity_x=0;
  169. static double imu_angular_velocity_y=0;
  170. static double imu_angular_velocity_z=0;
  171. static double imu_linear_acceleration_x=0;
  172. static double imu_linear_acceleration_y=0;
  173. static double imu_linear_acceleration_z =0;
  174. extern QFile * gpFileLastPos;//Save Last Positin
  175. static bool gbFileNDTUpdate;
  176. extern double garm_x ;
  177. extern double garm_y ;
  178. #include <QDateTime>
  179. //cv::Mat gmatimage;
  180. void ListenPoseSet(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  181. {
  182. iv::lidar::ndtpos pos;
  183. if(false == pos.ParseFromArray(strdata,nSize))
  184. {
  185. std::cout<<" ndtpos parse error."<<std::endl;
  186. return;
  187. }
  188. SetCurPose(pos.pose_x(),pos.pose_y(),pos.pose_yaw(),pos.pose_z(),pos.pose_pitch(),pos.pose_roll());
  189. }
  190. static void SetLocalMap()
  191. {
  192. pcl::PointCloud<pcl::PointXYZ>::Ptr local_ptr(new pcl::PointCloud<pcl::PointXYZ>());
  193. int nSize = global_map_ptr->size();
  194. int i;
  195. for(i=0;i<nSize;i++)
  196. {
  197. pcl::PointXYZ xp = global_map_ptr->at(i);
  198. if(sqrt(pow(xp.x - current_pose.x,2)+pow(xp.y-current_pose.y,2)+pow(xp.z-current_pose.z,2))<30)
  199. {
  200. local_ptr->push_back(xp);
  201. }
  202. }
  203. glastmappose = current_pose;
  204. local_map_ptr = local_ptr;
  205. std::cout<<"current map size is "<<local_map_ptr->size()<<std::endl;
  206. }
  207. static bool gbNDTRun = true;
  208. static bool gbGFRun = true;
  209. static bool gbLMRun= true;
  210. static std::thread * gpmapthread, * gpgpsfixthread,*gpsavelastthread;
  211. static bool gbNeedUpdate = false;
  212. static std::shared_ptr<gpu::GNormalDistributionsTransform> glocal_ndt;
  213. extern iv::gpspos glastndtgpspos;
  214. extern iv::gpspos gcurndtgpspos;
  215. extern iv::gpspos gcurgpsgpspos;
  216. extern bool gbGPSFix;
  217. extern int64_t gnLastGPSTime;
  218. static bool gbgpsupdatendt = false;
  219. static int gusemapindex = -1;
  220. static int gcurmapindex = -1;
  221. extern std::vector<iv::ndtmaptrace> gvector_trace;
  222. extern void * gpa,* gpb ,* gpc, * gpd;
  223. iv::gpspos PoseToGPS(iv::gpspos xori,pose xpose)
  224. {
  225. double x_o,y_o;
  226. GaussProjCal(xori.lon,xori.lat,&x_o,&y_o);
  227. double lon,lat;
  228. double hdg_o = (90 - xori.heading)*M_PI/180.0;
  229. double rel_x = xpose.x * cos(hdg_o) - xpose.y * sin(hdg_o);
  230. double rel_y = xpose.x * sin(hdg_o) + xpose.y * cos(hdg_o);
  231. GaussProjInvCal(x_o + rel_x,y_o + rel_y,&lon,&lat);
  232. double hdg_c = hdg_o + xpose.yaw;
  233. hdg_c = M_PI/2.0 - hdg_c;
  234. double heading = hdg_c * 180.0/M_PI;
  235. while(heading < 0)heading = heading + 360;
  236. while(heading >360)heading = heading - 360;
  237. iv::gpspos xgpspos;
  238. xgpspos.lon = lon;
  239. xgpspos.lat = lat;
  240. xgpspos.height = xpose.z + xori.height;
  241. xgpspos.heading = heading;
  242. xgpspos.pitch = xpose.pitch + xori.pitch;
  243. xgpspos.roll = xpose.roll + xori.roll;
  244. xgpspos.ve = xpose.vx * cos(hdg_o) - xpose.vy * sin(hdg_o);
  245. xgpspos.vn = xpose.vx * sin(hdg_o) + xpose.vy * cos(hdg_o);
  246. if((garm_x != 0)||(garm_y != 0)) //arm use to Convert pos to GPS Posision
  247. {
  248. GaussProjCal(xgpspos.lon,xgpspos.lat,&x_o,&y_o);
  249. hdg_o = (90 - xgpspos.heading)*M_PI/180.0;
  250. rel_x = garm_x *(-1) * cos(hdg_o) - garm_y *(-1) * sin(hdg_o);
  251. rel_y = garm_x *(-1) * sin(hdg_o) + garm_y *(-1) * cos(hdg_o);
  252. GaussProjInvCal(x_o + rel_x,y_o + rel_y,&lon,&lat);
  253. xgpspos.lon = lon;
  254. xgpspos.lat = lat;
  255. }
  256. return xgpspos;
  257. }
  258. pose CalcPose(iv::gpspos xori, iv::gpspos xcur)
  259. {
  260. double lon,lat;
  261. if((garm_x != 0)||(garm_y != 0)) //arm use to Convert pos to GPS Posision
  262. {
  263. double x_o,y_o;
  264. GaussProjCal(xcur.lon,xcur.lat,&x_o,&y_o);
  265. double hdg_o = (90 - xcur.heading)*M_PI/180.0;
  266. double rel_x = garm_x *(1) * cos(hdg_o) - garm_y *(1) * sin(hdg_o);
  267. double rel_y = garm_x *(1) * sin(hdg_o) + garm_y *(1) * cos(hdg_o);
  268. GaussProjInvCal(x_o + rel_x,y_o + rel_y,&lon,&lat);
  269. xcur.lon = lon;
  270. xcur.lat = lat;
  271. }
  272. double x_o,y_o,hdg_o;
  273. double x_c,y_c,hdg_c;
  274. GaussProjCal(xori.lon,xori.lat,&x_o,&y_o);
  275. GaussProjCal(xcur.lon,xcur.lat,&x_c,&y_c);
  276. double dis = sqrt(pow(x_c-x_o,2)+ pow(y_c-y_o,2));
  277. double rel_x0,rel_y0;
  278. rel_x0 = x_c -x_o;
  279. rel_y0 = y_c -y_o;
  280. double rel_x,rel_y;
  281. hdg_o = (90 - xori.heading)*M_PI/180.0;
  282. hdg_c = (90 - xcur.heading)*M_PI/180.0;
  283. rel_x = rel_x0 * cos(-hdg_o) - rel_y0 * sin(-hdg_o);
  284. rel_y = rel_x0 * sin(-hdg_o) + rel_y0 * cos(-hdg_o);
  285. double rel_hdg;
  286. rel_hdg = hdg_c - hdg_o;
  287. pose posex;
  288. posex.x = rel_x;
  289. posex.y = rel_y;
  290. posex.z = xcur.height - xori.height;
  291. posex.pitch = xcur.pitch - xori.pitch;
  292. posex.roll = xcur.roll - xori.roll;
  293. posex.yaw = rel_hdg;
  294. posex.vx = xcur.ve * cos(-hdg_o) - xcur.vn * sin(-hdg_o);
  295. posex.vy = xcur.ve * sin(-hdg_o) + xcur.vn * cos(-hdg_o);
  296. return posex;
  297. }
  298. static double gettracedis(int index,pose posex)
  299. {
  300. double fdismin = 1000000.;
  301. double zdiff = 0;
  302. int neari;
  303. if(index < 0)return 1000000.0;
  304. if(index>= gvector_trace.size())
  305. {
  306. return 1000000.0;
  307. }
  308. int i;
  309. std::vector<iv::ndttracepoint> vt = gvector_trace.at(index).mvector_trace;
  310. int nsize = vt.size();
  311. // std::cout<<"size is "<<nsize<<std::endl;
  312. for(i=0;i<nsize;i++)
  313. {
  314. double fdis = sqrt(pow(posex.x - vt.at(i).x,2) + pow(posex.y - vt.at(i).y,2));
  315. // std::cout<<"fdis is "<<fdis<<std::endl;
  316. if((fdis < fdismin) &&(fabs(posex.z - vt.at(i).z)<5))
  317. {
  318. fdismin = fdis;
  319. neari = i;
  320. zdiff = fabs(posex.z - vt.at(i).z);
  321. }
  322. }
  323. return fdismin;
  324. }
  325. static void getmindistrace(int & index, double & ftracedis)
  326. {
  327. double fdismin = 1000000.0;
  328. int xindexmin = -1;
  329. int i;
  330. int nsize = gvector_trace.size();
  331. for(i=0;i<nsize;i++)
  332. {
  333. pose posex = CalcPose(gvector_trace[i].mndtorigin,gcurndtgpspos);
  334. double fdis = gettracedis(i,posex);
  335. if(fdis<fdismin)
  336. {
  337. fdismin = fdis;
  338. xindexmin = i;
  339. }
  340. }
  341. if(xindexmin != -1)
  342. {
  343. ftracedis = fdismin;
  344. index = xindexmin;
  345. }
  346. else
  347. {
  348. index = -1;
  349. }
  350. }
  351. std::vector<std::shared_ptr<gpu::GNormalDistributionsTransform>> gvectoranh;
  352. #include <QTime>
  353. extern void pausecomm();
  354. extern void continuecomm();
  355. static void UseMap(int index)
  356. {
  357. pcl::PointCloud<pcl::PointXYZ>::Ptr xmap;
  358. xmap = boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>>(new pcl::PointCloud<pcl::PointXYZ>);
  359. QTime xTime;
  360. xTime.start();
  361. if(0 == pcl::io::loadPCDFile(gvector_trace.at(index).mstrpcdpath.data(),*xmap))
  362. {
  363. }
  364. else
  365. {
  366. std::cout<<"map size is 0"<<std::endl;
  367. return;
  368. }
  369. qDebug("load map time is %d",xTime.elapsed());
  370. pausecomm(); //Because cuda can pause process, avoid mutex comm, stop this process's comm
  371. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  372. pcl::PointCloud<pcl::PointXYZ>::Ptr map_ptr(new pcl::PointCloud<pcl::PointXYZ>(*xmap));
  373. std::shared_ptr<gpu::GNormalDistributionsTransform> new_anh_gpu_ndt_ptr =
  374. std::make_shared<gpu::GNormalDistributionsTransform>();
  375. new_anh_gpu_ndt_ptr->setResolution(ndt_res);
  376. new_anh_gpu_ndt_ptr->setInputTarget(map_ptr);
  377. new_anh_gpu_ndt_ptr->setMaximumIterations(max_iter);
  378. new_anh_gpu_ndt_ptr->setStepSize(step_size);
  379. new_anh_gpu_ndt_ptr->setTransformationEpsilon(trans_eps);
  380. pcl::PointCloud<pcl::PointXYZ>::Ptr dummy_scan_ptr(new pcl::PointCloud<pcl::PointXYZ>());
  381. pcl::PointXYZ dummy_point;
  382. dummy_scan_ptr->push_back(dummy_point);
  383. new_anh_gpu_ndt_ptr->setInputSource(dummy_scan_ptr);
  384. new_anh_gpu_ndt_ptr->align(Eigen::Matrix4f::Identity());
  385. pthread_mutex_lock(&mutex);
  386. glocal_ndt = new_anh_gpu_ndt_ptr;
  387. pthread_mutex_unlock(&mutex);
  388. continuecomm();
  389. // gvectoranh.push_back(new_anh_gpu_ndt_ptr);
  390. qDebug("ndt load finish time is %d",xTime.elapsed());
  391. gbNeedUpdate = true;
  392. gcurmapindex = index;
  393. std::cout<<"change map, index is "<<index<<std::endl;
  394. }
  395. void LocalMapUpdate(int n)
  396. {
  397. std::cout<<"LocalMap n is "<<n<<std::endl;
  398. int index;
  399. double ftracedis;
  400. int ncurindex = -1;
  401. int i;
  402. for(i=0;i<gvector_trace.size();i++)
  403. {
  404. // UseMap(i);
  405. // std::this_thread::sleep_for(std::chrono::milliseconds(1000));
  406. }
  407. while(gbLMRun)
  408. {
  409. getmindistrace(index,ftracedis);
  410. // std::cout<<"trace dis is "<<ftracedis<<std::endl;
  411. if(g_hasmap == false)
  412. {
  413. if(index >= 0)
  414. {
  415. if(ftracedis < 30)
  416. {
  417. UseMap(index);
  418. ncurindex = index;
  419. g_hasmap = true;
  420. }
  421. }
  422. }
  423. else
  424. {
  425. if(index != ncurindex)
  426. {
  427. pose posex = CalcPose(gvector_trace[ncurindex].mndtorigin,gcurndtgpspos);
  428. double fnowdis = gettracedis(ncurindex,posex);
  429. if((fnowdis - ftracedis)>5)
  430. {
  431. UseMap(index);
  432. ncurindex = index;
  433. g_hasmap = true;
  434. }
  435. }
  436. }
  437. if(ftracedis > 50)
  438. {
  439. std::cout<<" Out Range."<<std::endl;
  440. g_hasmap = false;
  441. }
  442. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  443. }
  444. }
  445. void SaveMonitor(bool * pbRun)
  446. {
  447. iv::gpspos xoldgpspos;
  448. xoldgpspos.lat = 39;
  449. xoldgpspos.lon = 117;
  450. while(*pbRun)
  451. {
  452. if(gpFileLastPos != 0)
  453. {
  454. if(gbFileNDTUpdate)
  455. {
  456. if((fabs(xoldgpspos.lat - gcurndtgpspos.lat)>0.0000005)||((fabs(xoldgpspos.lon - gcurndtgpspos.lon)>0.0000005)))
  457. {
  458. xoldgpspos = gcurndtgpspos;
  459. char str[1000];
  460. snprintf(str,1000,"%11.7f\t%11.7f\t%9.3f\t%6.2f\t%6.2f\t%6.2f\n ",
  461. xoldgpspos.lon,xoldgpspos.lat,xoldgpspos.height,
  462. xoldgpspos.heading,xoldgpspos.pitch,xoldgpspos.roll);
  463. gpFileLastPos->seek(0);
  464. gpFileLastPos->write(str,strnlen(str,1000));
  465. gpFileLastPos->flush();
  466. }
  467. gbFileNDTUpdate = false;
  468. }
  469. }
  470. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  471. }
  472. }
  473. void GPSPosMonitor(bool * pbRun)
  474. {
  475. if(gbGPSFix == false)
  476. {
  477. gcurndtgpspos = glastndtgpspos;
  478. }
  479. while(*pbRun)
  480. {
  481. int64_t nmsnow = std::chrono::system_clock::now().time_since_epoch().count()/1000000;
  482. if(abs(nmsnow - gnLastGPSTime)>1000)
  483. {
  484. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  485. continue;
  486. }
  487. if(gbGPSFix == true)
  488. {
  489. double x0,y0;
  490. double x,y;
  491. GaussProjCal(gcurndtgpspos.lon,gcurndtgpspos.lat,&x0,&y0);
  492. GaussProjCal(gcurgpsgpspos.lon,gcurgpsgpspos.lat,&x,&y);
  493. double dis = sqrt(pow(x-x0,2)+ pow(y-y0,2));
  494. double headdiff = fabs(gcurgpsgpspos.heading - gcurndtgpspos.heading);
  495. double zdiff = fabs(gcurgpsgpspos.height - gcurndtgpspos.height);
  496. if((dis> 10)||((headdiff>10)&&(headdiff<350))||(zdiff>5)||(g_hasmap == false)||(gbNeedGPSUpdateNDT))
  497. {
  498. givlog->info("NDTFIX","gps fix ndt pos. dis:%f headdiff:%f zdiff:%f map %d ndt %d",
  499. dis,headdiff,zdiff,g_hasmap,gbNeedGPSUpdateNDT);
  500. // gcurndtgpspos = gcurgpsgpspos;
  501. gbgpsupdatendt = true;
  502. // current_velocity_x = 0;
  503. // current_velocity_y = 0;
  504. // current_velocity_z = 0;
  505. // angular_velocity = 0;
  506. // gbNeedGPSUpdateNDT = false;
  507. if(g_hasmap == true)
  508. {
  509. int index = gcurmapindex;
  510. if((index >=0)&&(index < gvector_trace.size()))
  511. {
  512. }
  513. }
  514. }
  515. // else
  516. // {
  517. // if(gbgpsupdatendt)
  518. // {
  519. // gcurndtgpspos = gcurgpsgpspos;
  520. // gbgpsupdatendt = true;
  521. // current_velocity_x = 0;
  522. // current_velocity_y = 0;
  523. // current_velocity_z = 0;
  524. // angular_velocity = 0;
  525. // }
  526. // }
  527. }
  528. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  529. }
  530. }
  531. void ndt_match_Init(pcl::PointCloud<pcl::PointXYZ>::Ptr mappcd)
  532. {
  533. _tf_x = 0;
  534. _tf_y = 0;
  535. _tf_z = 0;
  536. _tf_roll = 0;
  537. _tf_pitch = 0;
  538. _tf_yaw = 0;
  539. Eigen::Translation3f tl_btol(_tf_x, _tf_y, _tf_z); // tl: translation
  540. Eigen::AngleAxisf rot_x_btol(_tf_roll, Eigen::Vector3f::UnitX()); // rot: rotation
  541. Eigen::AngleAxisf rot_y_btol(_tf_pitch, Eigen::Vector3f::UnitY());
  542. Eigen::AngleAxisf rot_z_btol(_tf_yaw, Eigen::Vector3f::UnitZ());
  543. tf_btol = (tl_btol * rot_z_btol * rot_y_btol * rot_x_btol).matrix();
  544. init_pos_set = 1;
  545. initial_pose.x = 0;
  546. initial_pose.y = 0;
  547. initial_pose.z = 0;
  548. initial_pose.roll = 0;
  549. initial_pose.pitch = 0;
  550. initial_pose.yaw = 0;
  551. localizer_pose.x = initial_pose.x;
  552. localizer_pose.y = initial_pose.y;
  553. localizer_pose.z = initial_pose.z;
  554. localizer_pose.roll = initial_pose.roll;
  555. localizer_pose.pitch = initial_pose.pitch;
  556. localizer_pose.yaw = initial_pose.yaw;
  557. previous_pose.x = initial_pose.x;
  558. previous_pose.y = initial_pose.y;
  559. previous_pose.z = initial_pose.z;
  560. previous_pose.roll = initial_pose.roll;
  561. previous_pose.pitch = initial_pose.pitch;
  562. previous_pose.yaw = initial_pose.yaw;
  563. current_pose.x = initial_pose.x;
  564. current_pose.y = initial_pose.y;
  565. current_pose.z = initial_pose.z;
  566. current_pose.roll = initial_pose.roll;
  567. current_pose.pitch = initial_pose.pitch;
  568. current_pose.yaw = initial_pose.yaw;
  569. current_velocity = 0;
  570. current_velocity_x = 0;
  571. current_velocity_y = 0;
  572. current_velocity_z = 0;
  573. angular_velocity = 0;
  574. // ndt.setResolution(ndt_res);
  575. // ndt.setStepSize(step_size);
  576. // ndt.setTransformationEpsilon(trans_eps);
  577. // ndt.setMaximumIterations(max_iter);
  578. // anh_gpu_ndt_ptr->setResolution();
  579. anh_gpu_ndt_ptr->setResolution(ndt_res);
  580. anh_gpu_ndt_ptr->setStepSize(step_size);
  581. anh_gpu_ndt_ptr->setTransformationEpsilon(trans_eps);
  582. anh_gpu_ndt_ptr->setMaximumIterations(max_iter);
  583. // ndt.align(*output_cloud, Eigen::Matrix4f::Identity());
  584. pcl::PointCloud<pcl::PointXYZ>::Ptr map_ptr(new pcl::PointCloud<pcl::PointXYZ>(*mappcd));
  585. std::cout<<"map size is"<<mappcd->size()<<std::endl;
  586. std::cout<<"ptr size is "<<map_ptr->size()<<std::endl;;
  587. global_map_ptr = map_ptr;
  588. // SetLocalMap();
  589. // pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_scan(new pcl::PointCloud<pcl::PointXYZ>());
  590. // pcl::VoxelGrid<pcl::PointXYZ> voxel_grid_filter;
  591. // voxel_grid_filter.setLeafSize(1.0,1.0,1.0);
  592. // voxel_grid_filter.setInputCloud(map_ptr);
  593. // voxel_grid_filter.filter(*filtered_scan);
  594. // std::cout<<"filter map size is "<<filtered_scan->size()<<std::endl;;
  595. // ndt.setInputTarget(map_ptr);
  596. // pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  597. // ndt.align(*output_cloud, Eigen::Matrix4f::Identity());
  598. gpset = iv::modulecomm::RegisterRecv("ndtposeset",ListenPoseSet);
  599. gppose = iv::modulecomm::RegisterSend("ndtpose",10000,3);
  600. if(map_ptr->size() == 0)
  601. {
  602. gbNDTRun = false;
  603. return;
  604. }
  605. std::shared_ptr<gpu::GNormalDistributionsTransform> new_anh_gpu_ndt_ptr =
  606. std::make_shared<gpu::GNormalDistributionsTransform>();
  607. new_anh_gpu_ndt_ptr->setResolution(ndt_res);
  608. new_anh_gpu_ndt_ptr->setInputTarget(map_ptr);
  609. new_anh_gpu_ndt_ptr->setMaximumIterations(max_iter);
  610. new_anh_gpu_ndt_ptr->setStepSize(step_size);
  611. new_anh_gpu_ndt_ptr->setTransformationEpsilon(trans_eps);
  612. pcl::PointCloud<pcl::PointXYZ>::Ptr dummy_scan_ptr(new pcl::PointCloud<pcl::PointXYZ>());
  613. pcl::PointXYZ dummy_point;
  614. dummy_scan_ptr->push_back(dummy_point);
  615. new_anh_gpu_ndt_ptr->setInputSource(dummy_scan_ptr);
  616. new_anh_gpu_ndt_ptr->align(Eigen::Matrix4f::Identity());
  617. pthread_mutex_lock(&mutex);
  618. anh_gpu_ndt_ptr = new_anh_gpu_ndt_ptr;
  619. pthread_mutex_unlock(&mutex);
  620. if(map_ptr->size()>0)map_loaded = 1;
  621. // gpmapthread = new std::thread(LocalMapUpdate,1);
  622. }
  623. void ndt_match_Init_nomap()
  624. {
  625. _tf_x = 0;
  626. _tf_y = 0;
  627. _tf_z = 0;
  628. _tf_roll = 0;
  629. _tf_pitch = 0;
  630. _tf_yaw = 0;
  631. Eigen::Translation3f tl_btol(_tf_x, _tf_y, _tf_z); // tl: translation
  632. Eigen::AngleAxisf rot_x_btol(_tf_roll, Eigen::Vector3f::UnitX()); // rot: rotation
  633. Eigen::AngleAxisf rot_y_btol(_tf_pitch, Eigen::Vector3f::UnitY());
  634. Eigen::AngleAxisf rot_z_btol(_tf_yaw, Eigen::Vector3f::UnitZ());
  635. tf_btol = (tl_btol * rot_z_btol * rot_y_btol * rot_x_btol).matrix();
  636. init_pos_set = 1;
  637. initial_pose.x = 0;
  638. initial_pose.y = 0;
  639. initial_pose.z = 0;
  640. initial_pose.roll = 0;
  641. initial_pose.pitch = 0;
  642. initial_pose.yaw = 0;
  643. localizer_pose.x = initial_pose.x;
  644. localizer_pose.y = initial_pose.y;
  645. localizer_pose.z = initial_pose.z;
  646. localizer_pose.roll = initial_pose.roll;
  647. localizer_pose.pitch = initial_pose.pitch;
  648. localizer_pose.yaw = initial_pose.yaw;
  649. previous_pose.x = initial_pose.x;
  650. previous_pose.y = initial_pose.y;
  651. previous_pose.z = initial_pose.z;
  652. previous_pose.roll = initial_pose.roll;
  653. previous_pose.pitch = initial_pose.pitch;
  654. previous_pose.yaw = initial_pose.yaw;
  655. current_pose.x = initial_pose.x;
  656. current_pose.y = initial_pose.y;
  657. current_pose.z = initial_pose.z;
  658. current_pose.roll = initial_pose.roll;
  659. current_pose.pitch = initial_pose.pitch;
  660. current_pose.yaw = initial_pose.yaw;
  661. current_velocity = 0;
  662. current_velocity_x = 0;
  663. current_velocity_y = 0;
  664. current_velocity_z = 0;
  665. angular_velocity = 0;
  666. anh_gpu_ndt_ptr->setResolution(ndt_res);
  667. anh_gpu_ndt_ptr->setStepSize(step_size);
  668. anh_gpu_ndt_ptr->setTransformationEpsilon(trans_eps);
  669. anh_gpu_ndt_ptr->setMaximumIterations(max_iter);
  670. gpmapthread = new std::thread(LocalMapUpdate,1);
  671. gbGFRun = true;
  672. gpgpsfixthread = new std::thread(GPSPosMonitor,&gbGFRun);
  673. gpsavelastthread = new std::thread(SaveMonitor,&gbGFRun);
  674. }
  675. void ndt_match_SetMap(pcl::PointCloud<pcl::PointXYZ>::Ptr mappcd)
  676. {
  677. if(mappcd->size() == 0 )return;
  678. pcl::PointCloud<pcl::PointXYZ>::Ptr map_ptr(new pcl::PointCloud<pcl::PointXYZ>(*mappcd));
  679. std::shared_ptr<gpu::GNormalDistributionsTransform> new_anh_gpu_ndt_ptr =
  680. std::make_shared<gpu::GNormalDistributionsTransform>();
  681. new_anh_gpu_ndt_ptr->setResolution(ndt_res);
  682. new_anh_gpu_ndt_ptr->setInputTarget(map_ptr);
  683. new_anh_gpu_ndt_ptr->setMaximumIterations(max_iter);
  684. new_anh_gpu_ndt_ptr->setStepSize(step_size);
  685. new_anh_gpu_ndt_ptr->setTransformationEpsilon(trans_eps);
  686. pcl::PointCloud<pcl::PointXYZ>::Ptr dummy_scan_ptr(new pcl::PointCloud<pcl::PointXYZ>());
  687. pcl::PointXYZ dummy_point;
  688. dummy_scan_ptr->push_back(dummy_point);
  689. new_anh_gpu_ndt_ptr->setInputSource(dummy_scan_ptr);
  690. new_anh_gpu_ndt_ptr->align(Eigen::Matrix4f::Identity());
  691. pthread_mutex_lock(&mutex);
  692. anh_gpu_ndt_ptr = new_anh_gpu_ndt_ptr;
  693. pthread_mutex_unlock(&mutex);
  694. if(map_ptr->size()>0)map_loaded = 1;
  695. }
  696. static double wrapToPm(double a_num, const double a_max)
  697. {
  698. if (a_num >= a_max)
  699. {
  700. a_num -= 2.0 * a_max;
  701. }
  702. return a_num;
  703. }
  704. static double wrapToPmPi(const double a_angle_rad)
  705. {
  706. return wrapToPm(a_angle_rad, M_PI);
  707. }
  708. static double calcDiffForRadian(const double lhs_rad, const double rhs_rad)
  709. {
  710. double diff_rad = lhs_rad - rhs_rad;
  711. if (diff_rad >= M_PI)
  712. diff_rad = diff_rad - 2 * M_PI;
  713. else if (diff_rad < -M_PI)
  714. diff_rad = diff_rad + 2 * M_PI;
  715. return diff_rad;
  716. }
  717. static unsigned int g_seq_old = 0;
  718. #include <QTime>
  719. bool isfirst = true;
  720. #include <QMutex>
  721. std::vector<iv::imudata> gvectorimu;
  722. QMutex gMuteximu;
  723. static void lidar_imu_calc(qint64 current_lidar_time)
  724. {
  725. int nsize;
  726. int i;
  727. gMuteximu.lock();
  728. nsize = gvectorimu.size();
  729. for(i=0;i<nsize;i++)
  730. {
  731. iv::imudata ximudata = gvectorimu[i];
  732. double ximu_angular_velocity_x,ximu_angular_velocity_y,ximu_angular_velocity_z;
  733. double ximu_linear_acceleration_x,ximu_linear_acceleration_y,ximu_linear_acceleration_z;
  734. if(current_lidar_time > ximudata.imutime)
  735. {
  736. ximu_angular_velocity_x = ximudata.imu_angular_velocity_x;
  737. ximu_angular_velocity_y = ximudata.imu_angular_velocity_y;
  738. ximu_angular_velocity_z = ximudata.imu_angular_velocity_z;
  739. ximu_linear_acceleration_x = ximudata.imu_linear_acceleration_x;
  740. ximu_linear_acceleration_y = ximudata.imu_linear_acceleration_y;
  741. ximu_linear_acceleration_z = ximudata.imu_linear_acceleration_z;
  742. qint64 current_time_imu = ximudata.imutime;
  743. // givlog->verbose("NDT","imu time is %ld",current_time_imu);
  744. static qint64 previous_time_imu = current_time_imu;
  745. double diff_time = (current_time_imu - previous_time_imu);
  746. diff_time = diff_time/1000.0;
  747. if(diff_time < 0)diff_time = 0.000001;
  748. if(diff_time > 0.1)diff_time = 0.1;
  749. if(current_time_imu < previous_time_imu)
  750. {
  751. std::cout<<"current time is old "<<current_time_imu<<std::endl;
  752. previous_time_imu = current_time_imu;
  753. continue;
  754. }
  755. double diff_imu_roll = ximu_angular_velocity_x * diff_time;
  756. double diff_imu_pitch = ximu_angular_velocity_y * diff_time;
  757. double diff_imu_yaw = ximu_angular_velocity_z * diff_time;
  758. current_pose_imu.roll += diff_imu_roll;
  759. current_pose_imu.pitch += diff_imu_pitch;
  760. current_pose_imu.yaw += diff_imu_yaw;
  761. double accX1 = ximu_linear_acceleration_x;
  762. double accY1 = std::cos(current_pose_imu.roll) * ximu_linear_acceleration_y -
  763. std::sin(current_pose_imu.roll) * ximu_linear_acceleration_z;
  764. double accZ1 = std::sin(current_pose_imu.roll) * ximu_linear_acceleration_y +
  765. std::cos(current_pose_imu.roll) * ximu_linear_acceleration_z;
  766. double accX2 = std::sin(current_pose_imu.pitch) * accZ1 + std::cos(current_pose_imu.pitch) * accX1;
  767. double accY2 = accY1;
  768. double accZ2 = std::cos(current_pose_imu.pitch) * accZ1 - std::sin(current_pose_imu.pitch) * accX1;
  769. double accX = std::cos(current_pose_imu.yaw) * accX2 - std::sin(current_pose_imu.yaw) * accY2;
  770. double accY = std::sin(current_pose_imu.yaw) * accX2 + std::cos(current_pose_imu.yaw) * accY2;
  771. double accZ = accZ2;
  772. offset_imu_x += current_velocity_imu_x * diff_time + accX * diff_time * diff_time / 2.0;
  773. offset_imu_y += current_velocity_imu_y * diff_time + accY * diff_time * diff_time / 2.0;
  774. offset_imu_z += current_velocity_imu_z * diff_time + accZ * diff_time * diff_time / 2.0;
  775. current_velocity_imu_x += accX * diff_time;
  776. current_velocity_imu_y += accY * diff_time;
  777. current_velocity_imu_z += accZ * diff_time;
  778. offset_imu_roll += diff_imu_roll;
  779. offset_imu_pitch += diff_imu_pitch;
  780. offset_imu_yaw += diff_imu_yaw;
  781. // guess_pose_imu.x = previous_pose.x + offset_imu_x;
  782. // guess_pose_imu.y = previous_pose.y + offset_imu_y;
  783. // guess_pose_imu.z = previous_pose.z + offset_imu_z;
  784. // guess_pose_imu.roll = previous_pose.roll + offset_imu_roll;
  785. // guess_pose_imu.pitch = previous_pose.pitch + offset_imu_pitch;
  786. // guess_pose_imu.yaw = previous_pose.yaw + offset_imu_yaw;
  787. predict_pose_imu.x = previous_pose.x + offset_imu_x;
  788. predict_pose_imu.y = previous_pose.y + offset_imu_y;
  789. predict_pose_imu.z = previous_pose.z + offset_imu_z;
  790. predict_pose_imu.roll = previous_pose.roll + offset_imu_roll;
  791. predict_pose_imu.pitch = previous_pose.pitch + offset_imu_pitch;
  792. predict_pose_imu.yaw = previous_pose.yaw + offset_imu_yaw;
  793. givlog->verbose("NDT","imu x:%f y:%f z:%f yaw:%f",offset_imu_x,
  794. offset_imu_y,offset_imu_z,offset_imu_yaw);
  795. previous_time_imu = current_time_imu;
  796. }
  797. else
  798. {
  799. break;;
  800. }
  801. }
  802. if(i>0)
  803. {
  804. gvectorimu.erase(gvectorimu.begin(),gvectorimu.begin()+i);
  805. }
  806. gMuteximu.unlock();
  807. // for(i=0;i<gvectorimu.size();i++)
  808. // {
  809. // iv::imudata ximudata = gvectorimu[i];
  810. // double ximu_angular_velocity_x,ximu_angular_velocity_y,ximu_angular_velocity_z;
  811. // double ximu_linear_acceleration_x,ximu_linear_acceleration_y,ximu_linear_acceleration_z;
  812. // if(current_lidar_time > ximudata.imutime)
  813. // {
  814. // gvectorimu.erase(gvectorimu.begin())
  815. // }
  816. // }
  817. }
  818. static void imu_calc(qint64 current_time_imu)
  819. {
  820. static qint64 previous_time_imu = current_time_imu;
  821. double diff_time = (current_time_imu - previous_time_imu);
  822. diff_time = diff_time/1000.0;
  823. if(current_time_imu < previous_time_imu)
  824. {
  825. std::cout<<"current time is old "<<current_time_imu<<std::endl;
  826. return;
  827. }
  828. double diff_imu_roll = imu_angular_velocity_x * diff_time;
  829. double diff_imu_pitch = imu_angular_velocity_y * diff_time;
  830. double diff_imu_yaw = imu_angular_velocity_z * diff_time;
  831. current_pose_imu.roll += diff_imu_roll;
  832. current_pose_imu.pitch += diff_imu_pitch;
  833. current_pose_imu.yaw += diff_imu_yaw;
  834. double accX1 = imu_linear_acceleration_x;
  835. double accY1 = std::cos(current_pose_imu.roll) * imu_linear_acceleration_y -
  836. std::sin(current_pose_imu.roll) * imu_linear_acceleration_z;
  837. double accZ1 = std::sin(current_pose_imu.roll) * imu_linear_acceleration_y +
  838. std::cos(current_pose_imu.roll) * imu_linear_acceleration_z;
  839. double accX2 = std::sin(current_pose_imu.pitch) * accZ1 + std::cos(current_pose_imu.pitch) * accX1;
  840. double accY2 = accY1;
  841. double accZ2 = std::cos(current_pose_imu.pitch) * accZ1 - std::sin(current_pose_imu.pitch) * accX1;
  842. double accX = std::cos(current_pose_imu.yaw) * accX2 - std::sin(current_pose_imu.yaw) * accY2;
  843. double accY = std::sin(current_pose_imu.yaw) * accX2 + std::cos(current_pose_imu.yaw) * accY2;
  844. double accZ = accZ2;
  845. offset_imu_x += current_velocity_imu_x * diff_time + accX * diff_time * diff_time / 2.0;
  846. offset_imu_y += current_velocity_imu_y * diff_time + accY * diff_time * diff_time / 2.0;
  847. offset_imu_z += current_velocity_imu_z * diff_time + accZ * diff_time * diff_time / 2.0;
  848. current_velocity_imu_x += accX * diff_time;
  849. current_velocity_imu_y += accY * diff_time;
  850. current_velocity_imu_z += accZ * diff_time;
  851. offset_imu_roll += diff_imu_roll;
  852. offset_imu_pitch += diff_imu_pitch;
  853. offset_imu_yaw += diff_imu_yaw;
  854. // guess_pose_imu.x = previous_pose.x + offset_imu_x;
  855. // guess_pose_imu.y = previous_pose.y + offset_imu_y;
  856. // guess_pose_imu.z = previous_pose.z + offset_imu_z;
  857. // guess_pose_imu.roll = previous_pose.roll + offset_imu_roll;
  858. // guess_pose_imu.pitch = previous_pose.pitch + offset_imu_pitch;
  859. // guess_pose_imu.yaw = previous_pose.yaw + offset_imu_yaw;
  860. predict_pose_imu.x = previous_pose.x + offset_imu_x;
  861. predict_pose_imu.y = previous_pose.y + offset_imu_y;
  862. predict_pose_imu.z = previous_pose.z + offset_imu_z;
  863. predict_pose_imu.roll = previous_pose.roll + offset_imu_roll;
  864. predict_pose_imu.pitch = previous_pose.pitch + offset_imu_pitch;
  865. predict_pose_imu.yaw = previous_pose.yaw + offset_imu_yaw;
  866. givlog->verbose("NDT","imu x:%f y:%f z:%f yaw:%f",offset_imu_x,
  867. offset_imu_y,offset_imu_z,offset_imu_yaw);
  868. previous_time_imu = current_time_imu;
  869. }
  870. void imu_update(qint64 current_time_imu,double imu_roll,double imu_pitch,double imu_yaw,
  871. double acceleration_x,double acceleration_y,
  872. double acceleration_z)
  873. {
  874. // std::cout << __func__ << std::endl;
  875. // double imu_angular_velocity_x,imu_angular_velocity_y,imu_angular_velocity_z;
  876. static double previous_time_imu = current_time_imu;
  877. double diff_time = (current_time_imu - previous_time_imu);
  878. diff_time = diff_time/1000.0;
  879. imu_roll = imu_roll * M_PI/180.0;
  880. imu_pitch = imu_pitch * M_PI/180.0;
  881. imu_yaw = (-1.0)*imu_yaw * M_PI/180.0;
  882. imu_yaw = imu_yaw + 2.0*M_PI;
  883. // imu_pitch = 0;
  884. // imu_roll = 0;
  885. imu_roll = wrapToPmPi(imu_roll);
  886. imu_pitch = wrapToPmPi(imu_pitch);
  887. imu_yaw = wrapToPmPi(imu_yaw);
  888. static double previous_imu_roll = imu_roll, previous_imu_pitch = imu_pitch, previous_imu_yaw = imu_yaw;
  889. const double diff_imu_roll = imu_roll - previous_imu_roll;
  890. const double diff_imu_pitch = imu_pitch - previous_imu_pitch;
  891. double diff_imu_yaw;
  892. if (fabs(imu_yaw - previous_imu_yaw) > M_PI)
  893. {
  894. if (imu_yaw > 0)
  895. diff_imu_yaw = (imu_yaw - previous_imu_yaw) - M_PI * 2;
  896. else
  897. diff_imu_yaw = -M_PI * 2 - (imu_yaw - previous_imu_yaw);
  898. }
  899. else
  900. diff_imu_yaw = imu_yaw - previous_imu_yaw;
  901. imu_linear_acceleration_x = acceleration_x;
  902. // imu_linear_acceleration_y = acceleration_y;
  903. // imu_linear_acceleration_z = acceleration_z;
  904. imu_linear_acceleration_y = 0;
  905. imu_linear_acceleration_z = 0;
  906. if (diff_time != 0)
  907. {
  908. imu_angular_velocity_x = diff_imu_roll / diff_time;
  909. imu_angular_velocity_y = diff_imu_pitch / diff_time;
  910. imu_angular_velocity_z = diff_imu_yaw / diff_time;
  911. }
  912. else
  913. {
  914. imu_angular_velocity_x = 0;
  915. imu_angular_velocity_y = 0;
  916. imu_angular_velocity_z = 0;
  917. }
  918. iv::imudata ximudata;
  919. ximudata.imutime = current_time_imu;
  920. ximudata.imu_linear_acceleration_x = imu_linear_acceleration_x;
  921. ximudata.imu_linear_acceleration_y = imu_linear_acceleration_y;
  922. ximudata.imu_linear_acceleration_z = imu_linear_acceleration_z;
  923. ximudata.imu_angular_velocity_x = imu_angular_velocity_x;
  924. ximudata.imu_angular_velocity_y = imu_angular_velocity_y;
  925. ximudata.imu_angular_velocity_z = imu_angular_velocity_z;
  926. gMuteximu.lock();
  927. gvectorimu.push_back(ximudata);
  928. gMuteximu.unlock();
  929. // imu_calc(current_time_imu);
  930. previous_time_imu = current_time_imu;
  931. previous_imu_roll = imu_roll;
  932. previous_imu_pitch = imu_pitch;
  933. previous_imu_yaw = imu_yaw;
  934. }
  935. void point_ndt(pcl::PointCloud<pcl::PointXYZ>::Ptr raw_scan)
  936. {
  937. static bool bNeedUpdateVel = false; //if gps update ndt, need update velocity
  938. qint64 current_scan_time = raw_scan->header.stamp;
  939. static qint64 old_scan_time = current_scan_time;
  940. if(gbNDTRun == false)return;
  941. bool bNotChangev = false;
  942. if(gbgpsupdatendt == true)
  943. {
  944. gcurndtgpspos = gcurgpsgpspos;
  945. gbgpsupdatendt = false;
  946. gbNeedGPSUpdateNDT = false;
  947. current_velocity_x = 0;
  948. current_velocity_y = 0;
  949. current_velocity_z = 0;
  950. angular_velocity = 0;
  951. bNeedUpdateVel = true;
  952. //
  953. //
  954. // gcurndtgpspos = gcurgpsgpspos;
  955. // current_pose = CalcPose(gvector_trace[gusemapindex].mndtorigin,gcurndtgpspos);
  956. // predict_pose_for_ndt = current_pose;
  957. current_velocity_imu_x = 0;
  958. current_velocity_imu_y = 0;
  959. current_velocity_imu_z = 0;
  960. gMuteximu.lock();
  961. gvectorimu.erase(gvectorimu.begin(),gvectorimu.begin() + gvectorimu.size());
  962. gMuteximu.unlock();
  963. bNotChangev = true;
  964. return;
  965. }
  966. // gbgpsupdatendt = false;
  967. if(g_hasmap == false)
  968. {
  969. return;
  970. }
  971. if(gbNeedUpdate)
  972. {
  973. pthread_mutex_lock(&mutex);
  974. // ndt = glocal_ndt;
  975. anh_gpu_ndt_ptr = glocal_ndt;
  976. pthread_mutex_unlock(&mutex);
  977. gusemapindex = gcurmapindex;
  978. gbNeedUpdate = false;
  979. }
  980. previous_pose = CalcPose(gvector_trace[gusemapindex].mndtorigin,gcurndtgpspos);
  981. if(bNeedUpdateVel == true)
  982. {
  983. bNeedUpdateVel = false;
  984. current_velocity_x = previous_pose.vx;
  985. current_velocity_y = previous_pose.vy;
  986. current_velocity_imu_x = current_velocity_x;
  987. current_velocity_imu_y = current_velocity_y;
  988. }
  989. givlog->verbose("previos pose is %f %f",previous_pose.x,previous_pose.y);
  990. // if(map_loaded == 0)
  991. // {
  992. // std::cout<<BOLDRED<<" point_ndt not set map."<<RESET<<std::endl;
  993. // return;
  994. // }
  995. pthread_mutex_lock(&mutex_pose);
  996. QTime xTime;
  997. xTime.start();
  998. // std::cout<<"time is "<<xTime.elapsed()<<std::endl;
  999. double voxel_leaf_size = 2.0;
  1000. double measurement_range = 200.0;
  1001. pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_scan(new pcl::PointCloud<pcl::PointXYZ>());
  1002. pcl::VoxelGrid<pcl::PointXYZ> voxel_grid_filter;
  1003. voxel_grid_filter.setLeafSize(voxel_leaf_size, voxel_leaf_size, voxel_leaf_size);
  1004. voxel_grid_filter.setInputCloud(raw_scan);
  1005. voxel_grid_filter.filter(*filtered_scan);
  1006. // std::cout<<"voxed time is "<<xTime.elapsed()<<std::endl;
  1007. // std::cout<<" seq is "<<raw_scan->header.seq<<std::endl;
  1008. // qDebug("seq = %d stamp = %d ",raw_scan->header.seq,raw_scan->header.stamp);
  1009. // std::cout<<"raw scan size is "<<raw_scan->size()<<" filtered scan size is "<<filtered_scan->size()<<std::endl;
  1010. // return;
  1011. matching_start = std::chrono::system_clock::now();
  1012. pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_scan_ptr(new pcl::PointCloud<pcl::PointXYZ>(*filtered_scan));
  1013. int scan_points_num = filtered_scan_ptr->size();
  1014. Eigen::Matrix4f t(Eigen::Matrix4f::Identity()); // base_link
  1015. Eigen::Matrix4f t2(Eigen::Matrix4f::Identity()); // localizer
  1016. std::chrono::time_point<std::chrono::system_clock> align_start, align_end, getFitnessScore_start,
  1017. getFitnessScore_end;
  1018. static double align_time, getFitnessScore_time = 0.0;
  1019. // std::cout<<"run hear"<<std::endl;
  1020. pthread_mutex_lock(&mutex);
  1021. // if (_method_type == MethodType::PCL_GENERIC)
  1022. // ndt.setInputSource(filtered_scan_ptr);
  1023. anh_gpu_ndt_ptr->setInputSource(filtered_scan_ptr);
  1024. // Guess the initial gross estimation of the transformation
  1025. // double diff_time = (current_scan_time - previous_scan_time).toSec();
  1026. double diff_time = 0.0;
  1027. if(g_seq_old != 0)
  1028. {
  1029. if((raw_scan->header.seq - g_seq_old)>0)
  1030. {
  1031. diff_time = raw_scan->header.seq - g_seq_old;
  1032. diff_time = diff_time * 0.1;
  1033. }
  1034. }
  1035. g_seq_old = raw_scan->header.seq;
  1036. diff_time = current_scan_time -old_scan_time;
  1037. diff_time = diff_time/1000.0;
  1038. old_scan_time = current_scan_time;
  1039. if(diff_time<=0)diff_time = 0.1;
  1040. if(diff_time>1.0)diff_time = 1.0;
  1041. // std::cout<<"diff time is "<<diff_time<<std::endl;
  1042. // std::cout<<" diff time is "<<diff_time<<std::endl;
  1043. // diff_time = 0.0;
  1044. // if (_offset == "linear")
  1045. // {
  1046. if(diff_time<0.1)diff_time = 0.1;
  1047. offset_x = current_velocity_x * diff_time;
  1048. offset_y = current_velocity_y * diff_time;
  1049. offset_z = current_velocity_z * diff_time;
  1050. offset_yaw = angular_velocity * diff_time;
  1051. // }
  1052. predict_pose.x = previous_pose.x + offset_x;
  1053. predict_pose.y = previous_pose.y + offset_y;
  1054. predict_pose.z = previous_pose.z + offset_z;
  1055. predict_pose.roll = previous_pose.roll;
  1056. predict_pose.pitch = previous_pose.pitch;
  1057. predict_pose.yaw = previous_pose.yaw + offset_yaw;
  1058. pose predict_pose_for_ndt;
  1059. givlog->verbose("NDT","previous x:%f y:%f z:%f yaw:%f",previous_pose.x,
  1060. previous_pose.y,previous_pose.z,previous_pose.yaw);
  1061. // if (_use_imu == true && _use_odom == true)
  1062. // imu_odom_calc(current_scan_time);
  1063. if (_use_imu == true && _use_odom == false)
  1064. {
  1065. lidar_imu_calc((current_scan_time-0));
  1066. }
  1067. // if (_use_imu == false && _use_odom == true)
  1068. // odom_calc(current_scan_time);
  1069. // if (_use_imu == true && _use_odom == true)
  1070. // predict_pose_for_ndt = predict_pose_imu_odom;
  1071. // else
  1072. // if (_use_imu == true && _use_odom == false)
  1073. // predict_pose_for_ndt = predict_pose_imu;
  1074. // else if (_use_imu == false && _use_odom == true)
  1075. // predict_pose_for_ndt = predict_pose_odom;
  1076. // else
  1077. // predict_pose_for_ndt = predict_pose;
  1078. if (_use_imu == true && _use_odom == false)
  1079. {
  1080. predict_pose_for_ndt = predict_pose_imu;
  1081. // predict_pose_for_ndt = predict_pose;
  1082. // predict_pose_for_ndt.yaw = predict_pose_imu.yaw;
  1083. }
  1084. else
  1085. {
  1086. predict_pose_for_ndt = predict_pose;
  1087. }
  1088. if(fabs(predict_pose_for_ndt.x -previous_pose.x)>10)
  1089. {
  1090. predict_pose_for_ndt = previous_pose;
  1091. }
  1092. if(fabs(predict_pose_for_ndt.y -previous_pose.y)>10)
  1093. {
  1094. predict_pose_for_ndt = previous_pose;
  1095. }
  1096. // predict_pose_for_ndt = predict_pose;
  1097. givlog->verbose("NDT","pre x:%f y:%f z:%f yaw:%f",predict_pose_for_ndt.x,
  1098. predict_pose_for_ndt.y,predict_pose_for_ndt.z,predict_pose_for_ndt.yaw);
  1099. // predict_pose_for_ndt = predict_pose;
  1100. Eigen::Translation3f init_translation(predict_pose_for_ndt.x, predict_pose_for_ndt.y, predict_pose_for_ndt.z);
  1101. Eigen::AngleAxisf init_rotation_x(predict_pose_for_ndt.roll, Eigen::Vector3f::UnitX());
  1102. Eigen::AngleAxisf init_rotation_y(predict_pose_for_ndt.pitch, Eigen::Vector3f::UnitY());
  1103. Eigen::AngleAxisf init_rotation_z(predict_pose_for_ndt.yaw, Eigen::Vector3f::UnitZ());
  1104. Eigen::Matrix4f init_guess = (init_translation * init_rotation_z * init_rotation_y * init_rotation_x) * tf_btol;
  1105. pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  1106. // std::cout<<"before ndt time is "<<xTime.elapsed()<<std::endl;
  1107. // std::cout<<"time is "<<xTime.elapsed()<<std::endl;
  1108. align_start = std::chrono::system_clock::now();
  1109. anh_gpu_ndt_ptr->align(init_guess);
  1110. align_end = std::chrono::system_clock::now();
  1111. if(xTime.elapsed()<90)
  1112. std::cout<<GREEN<<"after ndt time is "<<xTime.elapsed()<<RESET<<std::endl;
  1113. else
  1114. std::cout<<RED<<"after ndt time is "<<xTime.elapsed()<<RESET<<std::endl;
  1115. has_converged = anh_gpu_ndt_ptr->hasConverged();
  1116. t = anh_gpu_ndt_ptr->getFinalTransformation();
  1117. iteration = anh_gpu_ndt_ptr->getFinalNumIteration();
  1118. getFitnessScore_start = std::chrono::system_clock::now();
  1119. fitness_score = anh_gpu_ndt_ptr->getFitnessScore();
  1120. getFitnessScore_end = std::chrono::system_clock::now();
  1121. trans_probability = anh_gpu_ndt_ptr->getTransformationProbability();
  1122. std::cout<<"score: "<<fitness_score<<" trans_probability:"<<trans_probability<<std::endl;
  1123. // std::cout<<" scoure is "<<fitness_score<<std::endl;
  1124. // std::cout<<" iter is "<<iteration<<std::endl;
  1125. t2 = t * tf_btol.inverse();
  1126. getFitnessScore_time =
  1127. std::chrono::duration_cast<std::chrono::microseconds>(getFitnessScore_end - getFitnessScore_start).count() /
  1128. 1000.0;
  1129. pthread_mutex_unlock(&mutex);
  1130. tf::Matrix3x3 mat_l; // localizer
  1131. mat_l.setValue(static_cast<double>(t(0, 0)), static_cast<double>(t(0, 1)), static_cast<double>(t(0, 2)),
  1132. static_cast<double>(t(1, 0)), static_cast<double>(t(1, 1)), static_cast<double>(t(1, 2)),
  1133. static_cast<double>(t(2, 0)), static_cast<double>(t(2, 1)), static_cast<double>(t(2, 2)));
  1134. // Update localizer_pose
  1135. localizer_pose.x = t(0, 3);
  1136. localizer_pose.y = t(1, 3);
  1137. localizer_pose.z = t(2, 3);
  1138. mat_l.getRPY(localizer_pose.roll, localizer_pose.pitch, localizer_pose.yaw, 1);
  1139. // std::cout<<" local pose x is "<<localizer_pose.x<<std::endl;
  1140. tf::Matrix3x3 mat_b; // base_link
  1141. mat_b.setValue(static_cast<double>(t2(0, 0)), static_cast<double>(t2(0, 1)), static_cast<double>(t2(0, 2)),
  1142. static_cast<double>(t2(1, 0)), static_cast<double>(t2(1, 1)), static_cast<double>(t2(1, 2)),
  1143. static_cast<double>(t2(2, 0)), static_cast<double>(t2(2, 1)), static_cast<double>(t2(2, 2)));
  1144. // Update ndt_pose
  1145. ndt_pose.x = t2(0, 3);
  1146. ndt_pose.y = t2(1, 3);
  1147. ndt_pose.z = t2(2, 3);
  1148. // ndt_pose.x = localizer_pose.x;
  1149. // ndt_pose.y = localizer_pose.y;
  1150. // ndt_pose.z = localizer_pose.z;
  1151. mat_b.getRPY(ndt_pose.roll, ndt_pose.pitch, ndt_pose.yaw, 1);
  1152. givlog->verbose("NDT","calc x:%f y:%f z:%f yaw:%f",ndt_pose.x,
  1153. ndt_pose.y,ndt_pose.z,ndt_pose.yaw);
  1154. // Calculate the difference between ndt_pose and predict_pose
  1155. predict_pose_error = sqrt((ndt_pose.x - predict_pose_for_ndt.x) * (ndt_pose.x - predict_pose_for_ndt.x) +
  1156. (ndt_pose.y - predict_pose_for_ndt.y) * (ndt_pose.y - predict_pose_for_ndt.y) +
  1157. (ndt_pose.z - predict_pose_for_ndt.z) * (ndt_pose.z - predict_pose_for_ndt.z));
  1158. // std::cout<<" pose error is "<<predict_pose_error<<std::endl;
  1159. // std::cout<<"ndt pose x is "<<ndt_pose.x<<std::endl;
  1160. if (predict_pose_error <= (PREDICT_POSE_THRESHOLD*10*diff_time))
  1161. {
  1162. use_predict_pose = 0;
  1163. }
  1164. else
  1165. {
  1166. use_predict_pose = 1;
  1167. }
  1168. use_predict_pose = 0;
  1169. if (use_predict_pose == 0)
  1170. {
  1171. current_pose.x = ndt_pose.x;
  1172. current_pose.y = ndt_pose.y;
  1173. current_pose.z = ndt_pose.z;
  1174. current_pose.roll = ndt_pose.roll;
  1175. current_pose.pitch = ndt_pose.pitch;
  1176. current_pose.yaw = ndt_pose.yaw;
  1177. }
  1178. else
  1179. {
  1180. givlog->verbose("NDT","USE PREDICT POSE");
  1181. current_pose.x = predict_pose_for_ndt.x;
  1182. current_pose.y = predict_pose_for_ndt.y;
  1183. current_pose.z = predict_pose_for_ndt.z;
  1184. current_pose.roll = predict_pose_for_ndt.roll;
  1185. current_pose.pitch = predict_pose_for_ndt.pitch;
  1186. current_pose.yaw = predict_pose_for_ndt.yaw;
  1187. }
  1188. // std::cout<<" current pose x is "<<current_pose.x<<std::endl;
  1189. // Compute the velocity and acceleration
  1190. diff_x = current_pose.x - previous_pose.x;
  1191. diff_y = current_pose.y - previous_pose.y;
  1192. diff_z = current_pose.z - previous_pose.z;
  1193. diff_yaw = calcDiffForRadian(current_pose.yaw, previous_pose.yaw);
  1194. diff = sqrt(diff_x * diff_x + diff_y * diff_y + diff_z * diff_z);
  1195. current_velocity = (diff_time > 0) ? (diff / diff_time) : 0;
  1196. current_velocity_x = (diff_time > 0) ? (diff_x / diff_time) : 0;
  1197. current_velocity_y = (diff_time > 0) ? (diff_y / diff_time) : 0;
  1198. current_velocity_z = (diff_time > 0) ? (diff_z / diff_time) : 0;
  1199. angular_velocity = (diff_time > 0) ? (diff_yaw / diff_time) : 0;
  1200. current_pose.vx = current_velocity_x;
  1201. current_pose.vy = current_velocity_y;
  1202. current_velocity_smooth = (current_velocity + previous_velocity + previous_previous_velocity) / 3.0;
  1203. if (current_velocity_smooth < 0.2)
  1204. {
  1205. current_velocity_smooth = 0.0;
  1206. }
  1207. // bNotChangev = true;
  1208. if((diff_time > 0)&&(bNotChangev == false))
  1209. {
  1210. double aa = (current_velocity -previous_velocity)/diff_time;
  1211. if(fabs(aa)>5.0)
  1212. {
  1213. givlog->verbose("NDT","aa is %f",aa);
  1214. aa = fabs(5.0/aa);
  1215. current_velocity = previous_velocity + aa*(current_velocity -previous_velocity);
  1216. current_velocity_x = previous_velocity_x + aa *((current_velocity_x -previous_velocity_x));
  1217. current_velocity_y = previous_velocity_y + aa *((current_velocity_y -previous_velocity_y));
  1218. current_velocity_z = previous_velocity_z + aa *((current_velocity_z -previous_velocity_z));
  1219. }
  1220. }
  1221. current_accel = (diff_time > 0) ? ((current_velocity - previous_velocity) / diff_time) : 0;
  1222. current_accel_x = (diff_time > 0) ? ((current_velocity_x - previous_velocity_x) / diff_time) : 0;
  1223. current_accel_y = (diff_time > 0) ? ((current_velocity_y - previous_velocity_y) / diff_time) : 0;
  1224. current_accel_z = (diff_time > 0) ? ((current_velocity_z - previous_velocity_z) / diff_time) : 0;
  1225. // std::cout<<"fit time is "<<getFitnessScore_time<<std::endl;
  1226. gcurndtgpspos = PoseToGPS(gvector_trace[gcurmapindex].mndtorigin,current_pose);
  1227. // std::cout<<" pre x:"<<previous_pose.x<<" pre y:"<<previous_pose.y<<std::endl;
  1228. std::cout<<" x: "<<current_pose.x<<" y: "<<current_pose.y
  1229. <<" z: "<<current_pose.z<<" yaw:"<<current_pose.yaw
  1230. <<" vel: "<<current_velocity<<std::endl;
  1231. std::cout<<"NDT ve:"<<gcurndtgpspos.ve<<" vn:"<<gcurndtgpspos.vn
  1232. <<" GPS ve:"<<gcurgpsgpspos.ve<<" vn:"<<gcurgpsgpspos.vn<<std::endl;
  1233. gbFileNDTUpdate = true;
  1234. // gw->Updatexyyaw(current_pose.x,current_pose.y,current_pose.yaw);
  1235. current_pose_imu.x = current_pose.x;
  1236. current_pose_imu.y = current_pose.y;
  1237. current_pose_imu.z = current_pose.z;
  1238. current_pose_imu.roll = current_pose.roll;
  1239. current_pose_imu.pitch = current_pose.pitch;
  1240. current_pose_imu.yaw = current_pose.yaw;
  1241. current_velocity_imu_x = current_velocity_x;
  1242. current_velocity_imu_y = current_velocity_y;
  1243. current_velocity_imu_z = current_velocity_z;
  1244. current_velocity_imu_z = 0;
  1245. offset_imu_x = 0.0;
  1246. offset_imu_y = 0.0;
  1247. offset_imu_z = 0.0;
  1248. offset_imu_roll = 0.0;
  1249. offset_imu_pitch = 0.0;
  1250. offset_imu_yaw = 0.0;
  1251. // std::cout<<" vx is "<<current_velocity_x<<" vy is "<<current_velocity_y<<std::endl;
  1252. previous_pose.x = current_pose.x;
  1253. previous_pose.y = current_pose.y;
  1254. previous_pose.z = current_pose.z;
  1255. previous_pose.roll = current_pose.roll;
  1256. previous_pose.pitch = current_pose.pitch;
  1257. previous_pose.yaw = current_pose.yaw;
  1258. // previous_scan_time = current_scan_time;
  1259. previous_previous_velocity = previous_velocity;
  1260. previous_velocity = current_velocity;
  1261. previous_velocity_x = current_velocity_x;
  1262. previous_velocity_y = current_velocity_y;
  1263. previous_velocity_z = current_velocity_z;
  1264. previous_accel = current_accel;
  1265. pthread_mutex_lock(&mutex_read);
  1266. gindex++;
  1267. glidar_pose.accel = current_accel;
  1268. glidar_pose.accel_x = current_accel_x;
  1269. glidar_pose.accel_y = current_accel_y;
  1270. glidar_pose.accel_z = current_accel_z;
  1271. glidar_pose.vel = current_velocity;
  1272. glidar_pose.vel_x = current_velocity_x;
  1273. glidar_pose.vel_y = current_velocity_y;
  1274. glidar_pose.vel_z = current_velocity_z;
  1275. glidar_pose.mpose = current_pose;
  1276. pthread_mutex_unlock(&mutex_read);
  1277. pthread_mutex_unlock(&mutex_pose);
  1278. double hdg_o = (90 - gvector_trace[gcurmapindex].mndtorigin.heading)*M_PI/180.0;
  1279. double ndt_vn = current_velocity_x * cos(hdg_o) - current_velocity_y * sin(hdg_o);
  1280. double ndt_ve = current_velocity_x * sin(hdg_o) + current_velocity_y * cos(hdg_o);
  1281. double ndt_vd = current_accel_z;
  1282. std::cout<<std::setprecision(9)<<"gps lat:"<<gcurndtgpspos.lat<<" lon:"
  1283. <<gcurndtgpspos.lon<<" z:"<<gcurndtgpspos.height<<" heading:"
  1284. <<gcurndtgpspos.heading<<std::endl;
  1285. std::cout<<std::setprecision(6)<<std::endl;
  1286. double x0,y0;
  1287. double x,y;
  1288. GaussProjCal(gcurndtgpspos.lon,gcurndtgpspos.lat,&x0,&y0);
  1289. GaussProjCal(gcurgpsgpspos.lon,gcurgpsgpspos.lat,&x,&y);
  1290. double dis = sqrt(pow(x-x0,2)+ pow(y-y0,2));
  1291. double headdiff = fabs(gcurgpsgpspos.heading - gcurndtgpspos.heading);
  1292. double zdiff = fabs(gcurgpsgpspos.height - gcurndtgpspos.height);
  1293. std::cout<<" dis:"<<dis<<" headdiff:"<<headdiff<<" zdiff:"<<zdiff<<std::endl;
  1294. iv::lidar::ndtpos ndtpos;
  1295. ndtpos.set_lidartime(raw_scan->header.stamp/1000);
  1296. ndtpos.set_ndt_time(QDateTime::currentMSecsSinceEpoch());
  1297. ndtpos.set_accel(current_accel);
  1298. ndtpos.set_accel_x(current_accel_x);
  1299. ndtpos.set_accel_y(current_accel_y);
  1300. ndtpos.set_accel_z(current_accel_z);
  1301. ndtpos.set_vel(current_velocity);
  1302. ndtpos.set_vel_x(current_velocity_x);
  1303. ndtpos.set_vel_y(current_velocity_y);
  1304. ndtpos.set_vel_z(current_velocity_z);
  1305. ndtpos.set_fitness_score(fitness_score);
  1306. ndtpos.set_has_converged(has_converged);
  1307. ndtpos.set_id(0);
  1308. ndtpos.set_iteration(iteration);
  1309. ndtpos.set_trans_probability(trans_probability);
  1310. ndtpos.set_pose_pitch(current_pose.pitch);
  1311. ndtpos.set_pose_roll(current_pose.roll);
  1312. ndtpos.set_pose_yaw(current_pose.yaw);
  1313. ndtpos.set_pose_x(current_pose.x);
  1314. ndtpos.set_pose_y(current_pose.y);
  1315. ndtpos.set_pose_z(current_pose.z);
  1316. ndtpos.set_comp_time(xTime.elapsed());
  1317. int ndatasize = ndtpos.ByteSize();
  1318. char * strser = new char[ndatasize];
  1319. bool bSer = ndtpos.SerializeToArray(strser,ndatasize);
  1320. if(bSer)
  1321. {
  1322. iv::modulecomm::ModuleSendMsg(gpc,strser,ndatasize);
  1323. }
  1324. else
  1325. {
  1326. std::cout<<BOLDRED<<"ndtpos serialize error."<<RESET<<std::endl;
  1327. }
  1328. delete strser;
  1329. iv::lidar::ndtgpspos xndtgpspos;
  1330. xndtgpspos.set_lat(gcurndtgpspos.lat);
  1331. xndtgpspos.set_lon(gcurndtgpspos.lon);
  1332. xndtgpspos.set_heading(gcurndtgpspos.heading);
  1333. xndtgpspos.set_height(gcurndtgpspos.height);
  1334. xndtgpspos.set_pitch(gcurndtgpspos.pitch);
  1335. xndtgpspos.set_roll(gcurndtgpspos.roll);
  1336. xndtgpspos.set_tras_prob(trans_probability);
  1337. xndtgpspos.set_score(fitness_score);
  1338. xndtgpspos.set_vn(ndt_vn);
  1339. xndtgpspos.set_ve(ndt_ve);
  1340. xndtgpspos.set_vd(ndt_vd);
  1341. givlog->debug("ndtgpspos","lat:%11.7f lon:%11.7f height:%11.3f heading:%6.3f pitch:%6.3f roll:%6.3f vn:%6.3f ve:%6.3f vd:%6.3f trans_prob:%6.3f score:%6.3f",
  1342. xndtgpspos.lat(),xndtgpspos.lon(),xndtgpspos.height(),
  1343. xndtgpspos.heading(),xndtgpspos.pitch(),xndtgpspos.roll(),
  1344. xndtgpspos.vn(),xndtgpspos.ve(),xndtgpspos.vd(),
  1345. xndtgpspos.tras_prob(),xndtgpspos.score());
  1346. ndatasize = xndtgpspos.ByteSize();
  1347. strser = new char[ndatasize];
  1348. bSer = xndtgpspos.SerializeToArray(strser,ndatasize);
  1349. if(bSer)
  1350. {
  1351. std::cout<<"share msg."<<std::endl;
  1352. iv::modulecomm::ModuleSendMsg(gpd,strser,ndatasize);
  1353. }
  1354. else
  1355. {
  1356. std::cout<<BOLDRED<<"ndtgpspos serialize error."<<RESET<<std::endl;
  1357. }
  1358. delete strser;
  1359. if(trans_probability < 0.5)gbNeedGPSUpdateNDT = true;
  1360. else gbNeedGPSUpdateNDT = false;
  1361. }
  1362. int GetPose(int & curindex,iv::lidar_pose & xlidar_pose)
  1363. {
  1364. pthread_mutex_lock(&mutex_read);
  1365. if(curindex == gindex)
  1366. {
  1367. pthread_mutex_unlock(&mutex_read);
  1368. return 0;
  1369. }
  1370. curindex = gindex;
  1371. xlidar_pose = glidar_pose;
  1372. pthread_mutex_unlock(&mutex_read);
  1373. return 1;
  1374. }
  1375. void SetCurPose(double x0, double y0, double yaw0, double z0, double pitch0, double roll0)
  1376. {
  1377. std::cout<<"set pose"<<std::endl;
  1378. pthread_mutex_lock(&mutex_pose);
  1379. initial_pose.x = x0;
  1380. initial_pose.y = y0;
  1381. initial_pose.z = z0;
  1382. initial_pose.roll = roll0;
  1383. initial_pose.pitch = pitch0;
  1384. initial_pose.yaw = yaw0;
  1385. localizer_pose.x = initial_pose.x;
  1386. localizer_pose.y = initial_pose.y;
  1387. localizer_pose.z = initial_pose.z;
  1388. localizer_pose.roll = initial_pose.roll;
  1389. localizer_pose.pitch = initial_pose.pitch;
  1390. localizer_pose.yaw = initial_pose.yaw;
  1391. previous_pose.x = initial_pose.x;
  1392. previous_pose.y = initial_pose.y;
  1393. previous_pose.z = initial_pose.z;
  1394. previous_pose.roll = initial_pose.roll;
  1395. previous_pose.pitch = initial_pose.pitch;
  1396. previous_pose.yaw = initial_pose.yaw;
  1397. current_pose.x = initial_pose.x;
  1398. current_pose.y = initial_pose.y;
  1399. current_pose.z = initial_pose.z;
  1400. current_pose.roll = initial_pose.roll;
  1401. current_pose.pitch = initial_pose.pitch;
  1402. current_pose.yaw = initial_pose.yaw;
  1403. current_velocity = 0;
  1404. current_velocity_x = 0;
  1405. current_velocity_y = 0;
  1406. current_velocity_z = 0;
  1407. angular_velocity = 0;
  1408. pthread_mutex_unlock(&mutex_pose);
  1409. }
  1410. void SetRunState(bool bRun)
  1411. {
  1412. std::cout<<"set state."<<std::endl;
  1413. gbNDTRun = bRun;
  1414. }
  1415. void setuseimu(bool bUse)
  1416. {
  1417. _use_imu = bUse;
  1418. }