ndt_matching.cpp 59 KB

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