ndt_matching.cpp 57 KB

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