ndt_matching.cpp 30 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941
  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 <nav_msgs/Odometry.h>
  30. //#include <ros/ros.h>
  31. //#include <sensor_msgs/Imu.h>
  32. //#include <sensor_msgs/PointCloud2.h>
  33. //#include <std_msgs/Bool.h>
  34. //#include <std_msgs/Float32.h>
  35. //#include <std_msgs/String.h>
  36. //#include <velodyne_pointcloud/point_types.h>
  37. //#include <velodyne_pointcloud/rawdata.h>
  38. //#include <geometry_msgs/PoseWithCovarianceStamped.h>
  39. //#include <geometry_msgs/TwistStamped.h>
  40. #include <tf/tf.h>
  41. #include <tf/transform_broadcaster.h>
  42. #include <tf/transform_datatypes.h>
  43. #include <tf/transform_listener.h>
  44. #include <pcl/io/io.h>
  45. #include <pcl/io/pcd_io.h>
  46. #include <pcl/point_types.h>
  47. #include <pcl_conversions/pcl_conversions.h>
  48. //#include <ndt_cpu/NormalDistributionsTransform.h>
  49. #include <pcl/registration/ndt.h>
  50. #include <ndt_gpu/NormalDistributionsTransform.h>
  51. #include "ndtpos.pb.h"
  52. #ifdef USE_PCL_OPENMP
  53. #include <pcl_omp_registration/ndt.h>
  54. #endif
  55. #include <pcl_ros/point_cloud.h>
  56. #include <pcl_ros/transforms.h>
  57. //#include <autoware_config_msgs/ConfigNDT.h>
  58. //#include <autoware_msgs/NDTStat.h>
  59. #include "ndt_matching.h"
  60. #include "modulecomm.h"
  61. //the following are UBUNTU/LINUX ONLY terminal color codes.
  62. #define RESET "\033[0m"
  63. #define BLACK "\033[30m" /* Black */
  64. #define RED "\033[31m" /* Red */
  65. #define GREEN "\033[32m" /* Green */
  66. #define YELLOW "\033[33m" /* Yellow */
  67. #define BLUE "\033[34m" /* Blue */
  68. #define MAGENTA "\033[35m" /* Magenta */
  69. #define CYAN "\033[36m" /* Cyan */
  70. #define WHITE "\033[37m" /* White */
  71. #define BOLDBLACK "\033[1m\033[30m" /* Bold Black */
  72. #define BOLDRED "\033[1m\033[31m" /* Bold Red */
  73. #define BOLDGREEN "\033[1m\033[32m" /* Bold Green */
  74. #define BOLDYELLOW "\033[1m\033[33m" /* Bold Yellow */
  75. #define BOLDBLUE "\033[1m\033[34m" /* Bold Blue */
  76. #define BOLDMAGENTA "\033[1m\033[35m" /* Bold Magenta */
  77. #define BOLDCYAN "\033[1m\033[36m" /* Bold Cyan */
  78. #define BOLDWHITE "\033[1m\033[37m" /* Bold White */
  79. #define PREDICT_POSE_THRESHOLD 0.5
  80. #define Wa 0.4
  81. #define Wb 0.3
  82. #define Wc 0.3
  83. static int gindex = 0;
  84. iv::lidar_pose glidar_pose;
  85. void * gpset;
  86. void * gppose;
  87. enum class MethodType
  88. {
  89. PCL_GENERIC = 0,
  90. PCL_ANH = 1,
  91. PCL_ANH_GPU = 2,
  92. PCL_OPENMP = 3,
  93. };
  94. static MethodType _method_type = MethodType::PCL_GENERIC;
  95. static pose initial_pose, predict_pose, predict_pose_imu, predict_pose_odom, predict_pose_imu_odom, previous_pose,
  96. ndt_pose, current_pose, current_pose_imu, current_pose_odom, current_pose_imu_odom, localizer_pose;
  97. static double offset_x, offset_y, offset_z, offset_yaw; // current_pos - previous_pose
  98. static double offset_imu_x, offset_imu_y, offset_imu_z, offset_imu_roll, offset_imu_pitch, offset_imu_yaw;
  99. static double offset_odom_x, offset_odom_y, offset_odom_z, offset_odom_roll, offset_odom_pitch, offset_odom_yaw;
  100. static double offset_imu_odom_x, offset_imu_odom_y, offset_imu_odom_z, offset_imu_odom_roll, offset_imu_odom_pitch,
  101. offset_imu_odom_yaw;
  102. // Can't load if typed "pcl::PointCloud<pcl::PointXYZRGB> map, add;"
  103. static pcl::PointCloud<pcl::PointXYZ> map, add;
  104. // If the map is loaded, map_loaded will be 1.
  105. static int map_loaded = 0;
  106. static int _use_gnss = 1;
  107. static int init_pos_set = 0;
  108. static pcl::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> ndt;
  109. //static cpu::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> anh_ndt;
  110. #ifdef CUDA_FOUND
  111. static std::shared_ptr<gpu::GNormalDistributionsTransform> anh_gpu_ndt_ptr =
  112. std::make_shared<gpu::GNormalDistributionsTransform>();
  113. #endif
  114. #ifdef USE_PCL_OPENMP
  115. static pcl_omp::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> omp_ndt;
  116. #endif
  117. // Default values
  118. static int max_iter = 30; // Maximum iterations
  119. static float ndt_res = 1.0; // Resolution
  120. static double step_size = 0.1; // Step size
  121. static double trans_eps = 0.01; // Transformation epsilon
  122. //static ros::Publisher predict_pose_pub;
  123. //static geometry_msgs::PoseStamped predict_pose_msg;
  124. //static ros::Publisher predict_pose_imu_pub;
  125. //static geometry_msgs::PoseStamped predict_pose_imu_msg;
  126. //static ros::Publisher predict_pose_odom_pub;
  127. //static geometry_msgs::PoseStamped predict_pose_odom_msg;
  128. //static ros::Publisher predict_pose_imu_odom_pub;
  129. //static geometry_msgs::PoseStamped predict_pose_imu_odom_msg;
  130. //static ros::Publisher ndt_pose_pub;
  131. //static geometry_msgs::PoseStamped ndt_pose_msg;
  132. // current_pose is published by vel_pose_mux
  133. /*
  134. static ros::Publisher current_pose_pub;
  135. static geometry_msgs::PoseStamped current_pose_msg;
  136. */
  137. //static ros::Publisher localizer_pose_pub;
  138. //static geometry_msgs::PoseStamped localizer_pose_msg;
  139. //static ros::Publisher estimate_twist_pub;
  140. //static geometry_msgs::TwistStamped estimate_twist_msg;
  141. //static ros::Duration scan_duration;
  142. static double exe_time = 0.0;
  143. static bool has_converged;
  144. static int iteration = 0;
  145. static double fitness_score = 0.0;
  146. static double trans_probability = 0.0;
  147. static double diff = 0.0;
  148. static double diff_x = 0.0, diff_y = 0.0, diff_z = 0.0, diff_yaw;
  149. static double current_velocity = 0.0, previous_velocity = 0.0, previous_previous_velocity = 0.0; // [m/s]
  150. static double current_velocity_x = 0.0, previous_velocity_x = 0.0;
  151. static double current_velocity_y = 0.0, previous_velocity_y = 0.0;
  152. static double current_velocity_z = 0.0, previous_velocity_z = 0.0;
  153. // static double current_velocity_yaw = 0.0, previous_velocity_yaw = 0.0;
  154. static double current_velocity_smooth = 0.0;
  155. static double current_velocity_imu_x = 0.0;
  156. static double current_velocity_imu_y = 0.0;
  157. static double current_velocity_imu_z = 0.0;
  158. static double current_accel = 0.0, previous_accel = 0.0; // [m/s^2]
  159. static double current_accel_x = 0.0;
  160. static double current_accel_y = 0.0;
  161. static double current_accel_z = 0.0;
  162. // static double current_accel_yaw = 0.0;
  163. static double angular_velocity = 0.0;
  164. static int use_predict_pose = 0;
  165. //static ros::Publisher estimated_vel_mps_pub, estimated_vel_kmph_pub, estimated_vel_pub;
  166. //static std_msgs::Float32 estimated_vel_mps, estimated_vel_kmph, previous_estimated_vel_kmph;
  167. static std::chrono::time_point<std::chrono::system_clock> matching_start, matching_end;
  168. //static ros::Publisher time_ndt_matching_pub;
  169. //static std_msgs::Float32 time_ndt_matching;
  170. static int _queue_size = 1000;
  171. //static ros::Publisher ndt_stat_pub;
  172. //static autoware_msgs::NDTStat ndt_stat_msg;
  173. static double predict_pose_error = 0.0;
  174. static double _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw;
  175. static Eigen::Matrix4f tf_btol;
  176. static std::string _localizer = "velodyne";
  177. static std::string _offset = "linear"; // linear, zero, quadratic
  178. //static ros::Publisher ndt_reliability_pub;
  179. //static std_msgs::Float32 ndt_reliability;
  180. static bool _get_height = false;
  181. static bool _use_local_transform = false;
  182. static bool _use_imu = false;
  183. static bool _use_odom = false;
  184. static bool _imu_upside_down = false;
  185. static bool _output_log_data = false;
  186. static std::string _imu_topic = "/imu_raw";
  187. static std::ofstream ofs;
  188. static std::string filename;
  189. //static sensor_msgs::Imu imu;
  190. //static nav_msgs::Odometry odom;
  191. // static tf::TransformListener local_transform_listener;
  192. static tf::StampedTransform local_transform;
  193. static unsigned int points_map_num = 0;
  194. pthread_mutex_t mutex;
  195. pthread_mutex_t mutex_read;
  196. pthread_mutex_t mutex_pose;
  197. pcl::PointCloud<pcl::PointXYZ>::Ptr local_map_ptr;
  198. pcl::PointCloud<pcl::PointXYZ>::Ptr global_map_ptr;
  199. pose glastmappose;
  200. #include <QDateTime>
  201. //cv::Mat gmatimage;
  202. void ListenPoseSet(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  203. {
  204. iv::lidar::ndtpos pos;
  205. if(false == pos.ParseFromArray(strdata,nSize))
  206. {
  207. std::cout<<" ndtpos parse error."<<std::endl;
  208. return;
  209. }
  210. SetCurPose(pos.pose_x(),pos.pose_y(),pos.pose_yaw(),pos.pose_z(),pos.pose_pitch(),pos.pose_roll());
  211. }
  212. static void SetLocalMap()
  213. {
  214. pcl::PointCloud<pcl::PointXYZ>::Ptr local_ptr(new pcl::PointCloud<pcl::PointXYZ>());
  215. int nSize = global_map_ptr->size();
  216. int i;
  217. for(i=0;i<nSize;i++)
  218. {
  219. pcl::PointXYZ xp = global_map_ptr->at(i);
  220. if(sqrt(pow(xp.x - current_pose.x,2)+pow(xp.y-current_pose.y,2)+pow(xp.z-current_pose.z,2))<30)
  221. {
  222. local_ptr->push_back(xp);
  223. }
  224. }
  225. glastmappose = current_pose;
  226. local_map_ptr = local_ptr;
  227. std::cout<<"current map size is "<<local_map_ptr->size()<<std::endl;
  228. }
  229. static bool gbNDTRun = true;
  230. static bool gbLMRun= true;
  231. static std::thread * gpmapthread;
  232. static bool gbNeedUpdate = false;
  233. static pcl::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> glocal_ndt;
  234. void LocalMapUpdate(int n)
  235. {
  236. std::cout<<"LocalMap n is "<<n<<std::endl;
  237. while(gbLMRun)
  238. {
  239. if(sqrt(pow(glastmappose.x-current_pose.x,2)+pow(glastmappose.y-current_pose.y,2)+pow(glastmappose.z-current_pose.z,2))>5)
  240. {
  241. SetLocalMap();
  242. // pcl::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> new_ndt;
  243. // pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  244. // new_ndt.setResolution(ndt_res);
  245. // // new_ndt.setInputTarget(map_ptr);
  246. // new_ndt.setInputTarget(local_map_ptr);
  247. // // new_ndt.setInputTarget(filtered_scan);
  248. // new_ndt.setMaximumIterations(max_iter);
  249. // new_ndt.setStepSize(step_size);
  250. // new_ndt.setTransformationEpsilon(trans_eps);
  251. // new_ndt.align(*output_cloud, Eigen::Matrix4f::Identity());
  252. // pthread_mutex_lock(&mutex);
  253. // glocal_ndt = new_ndt;
  254. // pthread_mutex_unlock(&mutex);
  255. gbNeedUpdate = true;
  256. }
  257. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  258. }
  259. }
  260. void ndt_match_Init(pcl::PointCloud<pcl::PointXYZ>::Ptr mappcd)
  261. {
  262. _tf_x = 0;
  263. _tf_y = 0;
  264. _tf_z = 0;
  265. _tf_roll = 0;
  266. _tf_pitch = 0;
  267. _tf_yaw = 0;
  268. Eigen::Translation3f tl_btol(_tf_x, _tf_y, _tf_z); // tl: translation
  269. Eigen::AngleAxisf rot_x_btol(_tf_roll, Eigen::Vector3f::UnitX()); // rot: rotation
  270. Eigen::AngleAxisf rot_y_btol(_tf_pitch, Eigen::Vector3f::UnitY());
  271. Eigen::AngleAxisf rot_z_btol(_tf_yaw, Eigen::Vector3f::UnitZ());
  272. tf_btol = (tl_btol * rot_z_btol * rot_y_btol * rot_x_btol).matrix();
  273. init_pos_set = 1;
  274. initial_pose.x = 0;
  275. initial_pose.y = 0;
  276. initial_pose.z = 0;
  277. initial_pose.roll = 0;
  278. initial_pose.pitch = 0;
  279. initial_pose.yaw = 0;
  280. localizer_pose.x = initial_pose.x;
  281. localizer_pose.y = initial_pose.y;
  282. localizer_pose.z = initial_pose.z;
  283. localizer_pose.roll = initial_pose.roll;
  284. localizer_pose.pitch = initial_pose.pitch;
  285. localizer_pose.yaw = initial_pose.yaw;
  286. previous_pose.x = initial_pose.x;
  287. previous_pose.y = initial_pose.y;
  288. previous_pose.z = initial_pose.z;
  289. previous_pose.roll = initial_pose.roll;
  290. previous_pose.pitch = initial_pose.pitch;
  291. previous_pose.yaw = initial_pose.yaw;
  292. current_pose.x = initial_pose.x;
  293. current_pose.y = initial_pose.y;
  294. current_pose.z = initial_pose.z;
  295. current_pose.roll = initial_pose.roll;
  296. current_pose.pitch = initial_pose.pitch;
  297. current_pose.yaw = initial_pose.yaw;
  298. current_velocity = 0;
  299. current_velocity_x = 0;
  300. current_velocity_y = 0;
  301. current_velocity_z = 0;
  302. angular_velocity = 0;
  303. // ndt.setResolution(ndt_res);
  304. // ndt.setStepSize(step_size);
  305. // ndt.setTransformationEpsilon(trans_eps);
  306. // ndt.setMaximumIterations(max_iter);
  307. // anh_gpu_ndt_ptr->setResolution();
  308. anh_gpu_ndt_ptr->setResolution(ndt_res);
  309. anh_gpu_ndt_ptr->setStepSize(step_size);
  310. anh_gpu_ndt_ptr->setTransformationEpsilon(trans_eps);
  311. anh_gpu_ndt_ptr->setMaximumIterations(max_iter);
  312. // ndt.align(*output_cloud, Eigen::Matrix4f::Identity());
  313. pcl::PointCloud<pcl::PointXYZ>::Ptr map_ptr(new pcl::PointCloud<pcl::PointXYZ>(*mappcd));
  314. // int i;
  315. // for(i=0;i<map.size();i++)
  316. // {
  317. // pcl::PointXYZ px;
  318. // pcl::PointXYZI pxi;
  319. // pxi = mappcd->at(i);
  320. // px.x = pxi.x;
  321. // px.y = pxi.y;
  322. // px.z = pxi.z;
  323. // map_ptr->push_back(px);
  324. // ++map_ptr->width;
  325. //// px.x = mappcd->at(i).x;
  326. // }
  327. std::cout<<"map size is"<<mappcd->size()<<std::endl;
  328. std::cout<<"ptr size is "<<map_ptr->size()<<std::endl;;
  329. global_map_ptr = map_ptr;
  330. // SetLocalMap();
  331. // pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_scan(new pcl::PointCloud<pcl::PointXYZ>());
  332. // pcl::VoxelGrid<pcl::PointXYZ> voxel_grid_filter;
  333. // voxel_grid_filter.setLeafSize(1.0,1.0,1.0);
  334. // voxel_grid_filter.setInputCloud(map_ptr);
  335. // voxel_grid_filter.filter(*filtered_scan);
  336. // std::cout<<"filter map size is "<<filtered_scan->size()<<std::endl;;
  337. // ndt.setInputTarget(map_ptr);
  338. // pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  339. // ndt.align(*output_cloud, Eigen::Matrix4f::Identity());
  340. gpset = iv::modulecomm::RegisterRecv("ndtposeset",ListenPoseSet);
  341. gppose = iv::modulecomm::RegisterSend("ndtpose",10000,3);
  342. if(map_ptr->size() == 0)
  343. {
  344. gbNDTRun = false;
  345. return;
  346. }
  347. std::shared_ptr<gpu::GNormalDistributionsTransform> new_anh_gpu_ndt_ptr =
  348. std::make_shared<gpu::GNormalDistributionsTransform>();
  349. new_anh_gpu_ndt_ptr->setResolution(ndt_res);
  350. new_anh_gpu_ndt_ptr->setInputTarget(map_ptr);
  351. new_anh_gpu_ndt_ptr->setMaximumIterations(max_iter);
  352. new_anh_gpu_ndt_ptr->setStepSize(step_size);
  353. new_anh_gpu_ndt_ptr->setTransformationEpsilon(trans_eps);
  354. pcl::PointCloud<pcl::PointXYZ>::Ptr dummy_scan_ptr(new pcl::PointCloud<pcl::PointXYZ>());
  355. pcl::PointXYZ dummy_point;
  356. dummy_scan_ptr->push_back(dummy_point);
  357. new_anh_gpu_ndt_ptr->setInputSource(dummy_scan_ptr);
  358. new_anh_gpu_ndt_ptr->align(Eigen::Matrix4f::Identity());
  359. pthread_mutex_lock(&mutex);
  360. anh_gpu_ndt_ptr = new_anh_gpu_ndt_ptr;
  361. pthread_mutex_unlock(&mutex);
  362. if(map_ptr->size()>0)map_loaded = 1;
  363. // gpmapthread = new std::thread(LocalMapUpdate,1);
  364. }
  365. void ndt_match_SetMap(pcl::PointCloud<pcl::PointXYZ>::Ptr mappcd)
  366. {
  367. if(mappcd->size() == 0 )return;
  368. pcl::PointCloud<pcl::PointXYZ>::Ptr map_ptr(new pcl::PointCloud<pcl::PointXYZ>(*mappcd));
  369. std::shared_ptr<gpu::GNormalDistributionsTransform> new_anh_gpu_ndt_ptr =
  370. std::make_shared<gpu::GNormalDistributionsTransform>();
  371. new_anh_gpu_ndt_ptr->setResolution(ndt_res);
  372. new_anh_gpu_ndt_ptr->setInputTarget(map_ptr);
  373. new_anh_gpu_ndt_ptr->setMaximumIterations(max_iter);
  374. new_anh_gpu_ndt_ptr->setStepSize(step_size);
  375. new_anh_gpu_ndt_ptr->setTransformationEpsilon(trans_eps);
  376. pcl::PointCloud<pcl::PointXYZ>::Ptr dummy_scan_ptr(new pcl::PointCloud<pcl::PointXYZ>());
  377. pcl::PointXYZ dummy_point;
  378. dummy_scan_ptr->push_back(dummy_point);
  379. new_anh_gpu_ndt_ptr->setInputSource(dummy_scan_ptr);
  380. new_anh_gpu_ndt_ptr->align(Eigen::Matrix4f::Identity());
  381. pthread_mutex_lock(&mutex);
  382. anh_gpu_ndt_ptr = new_anh_gpu_ndt_ptr;
  383. pthread_mutex_unlock(&mutex);
  384. if(map_ptr->size()>0)map_loaded = 1;
  385. }
  386. static double wrapToPm(double a_num, const double a_max)
  387. {
  388. if (a_num >= a_max)
  389. {
  390. a_num -= 2.0 * a_max;
  391. }
  392. return a_num;
  393. }
  394. static double wrapToPmPi(const double a_angle_rad)
  395. {
  396. return wrapToPm(a_angle_rad, M_PI);
  397. }
  398. static double calcDiffForRadian(const double lhs_rad, const double rhs_rad)
  399. {
  400. double diff_rad = lhs_rad - rhs_rad;
  401. if (diff_rad >= M_PI)
  402. diff_rad = diff_rad - 2 * M_PI;
  403. else if (diff_rad < -M_PI)
  404. diff_rad = diff_rad + 2 * M_PI;
  405. return diff_rad;
  406. }
  407. static unsigned int g_seq_old = 0;
  408. #include <QTime>
  409. void point_ndt(pcl::PointCloud<pcl::PointXYZ>::Ptr raw_scan)
  410. {
  411. if(gbNDTRun == false)return;
  412. if(gbNeedUpdate)
  413. {
  414. pthread_mutex_lock(&mutex);
  415. // ndt = glocal_ndt;
  416. pthread_mutex_unlock(&mutex);
  417. gbNeedUpdate = false;
  418. std::cout<<BOLDRED<<"map size is "<<local_map_ptr->size()<<RESET<<std::endl;
  419. }
  420. if(map_loaded == 0)
  421. {
  422. std::cout<<BOLDRED<<" point_ndt not set map."<<RESET<<std::endl;
  423. return;
  424. }
  425. pthread_mutex_lock(&mutex_pose);
  426. QTime xTime;
  427. xTime.start();
  428. // std::cout<<"time is "<<xTime.elapsed()<<std::endl;
  429. double voxel_leaf_size = 2.0;
  430. double measurement_range = 200.0;
  431. pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_scan(new pcl::PointCloud<pcl::PointXYZ>());
  432. pcl::VoxelGrid<pcl::PointXYZ> voxel_grid_filter;
  433. voxel_grid_filter.setLeafSize(voxel_leaf_size, voxel_leaf_size, voxel_leaf_size);
  434. voxel_grid_filter.setInputCloud(raw_scan);
  435. voxel_grid_filter.filter(*filtered_scan);
  436. std::cout<<"voxed time is "<<xTime.elapsed()<<std::endl;
  437. // std::cout<<" seq is "<<raw_scan->header.seq<<std::endl;
  438. // qDebug("seq = %d stamp = %d ",raw_scan->header.seq,raw_scan->header.stamp);
  439. // std::cout<<"raw scan size is "<<raw_scan->size()<<" filtered scan size is "<<filtered_scan->size()<<std::endl;
  440. // return;
  441. matching_start = std::chrono::system_clock::now();
  442. pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_scan_ptr(new pcl::PointCloud<pcl::PointXYZ>(*filtered_scan));
  443. int scan_points_num = filtered_scan_ptr->size();
  444. Eigen::Matrix4f t(Eigen::Matrix4f::Identity()); // base_link
  445. Eigen::Matrix4f t2(Eigen::Matrix4f::Identity()); // localizer
  446. std::chrono::time_point<std::chrono::system_clock> align_start, align_end, getFitnessScore_start,
  447. getFitnessScore_end;
  448. static double align_time, getFitnessScore_time = 0.0;
  449. // std::cout<<"run hear"<<std::endl;
  450. pthread_mutex_lock(&mutex);
  451. // if (_method_type == MethodType::PCL_GENERIC)
  452. // ndt.setInputSource(filtered_scan_ptr);
  453. anh_gpu_ndt_ptr->setInputSource(filtered_scan_ptr);
  454. // Guess the initial gross estimation of the transformation
  455. // double diff_time = (current_scan_time - previous_scan_time).toSec();
  456. double diff_time = 0.0;
  457. if(g_seq_old != 0)
  458. {
  459. if((raw_scan->header.seq - g_seq_old)>0)
  460. {
  461. diff_time = raw_scan->header.seq - g_seq_old;
  462. diff_time = diff_time * 0.1;
  463. }
  464. }
  465. g_seq_old = raw_scan->header.seq;
  466. // std::cout<<" diff time is "<<diff_time<<std::endl;
  467. // diff_time = 0.0;
  468. // if (_offset == "linear")
  469. // {
  470. diff_time = 0.1;
  471. offset_x = current_velocity_x * diff_time;
  472. offset_y = current_velocity_y * diff_time;
  473. offset_z = current_velocity_z * diff_time;
  474. offset_yaw = angular_velocity * diff_time;
  475. // }
  476. predict_pose.x = previous_pose.x + offset_x;
  477. predict_pose.y = previous_pose.y + offset_y;
  478. predict_pose.z = previous_pose.z + offset_z;
  479. predict_pose.roll = previous_pose.roll;
  480. predict_pose.pitch = previous_pose.pitch;
  481. predict_pose.yaw = previous_pose.yaw + offset_yaw;
  482. pose predict_pose_for_ndt;
  483. predict_pose_for_ndt = predict_pose;
  484. Eigen::Translation3f init_translation(predict_pose_for_ndt.x, predict_pose_for_ndt.y, predict_pose_for_ndt.z);
  485. Eigen::AngleAxisf init_rotation_x(predict_pose_for_ndt.roll, Eigen::Vector3f::UnitX());
  486. Eigen::AngleAxisf init_rotation_y(predict_pose_for_ndt.pitch, Eigen::Vector3f::UnitY());
  487. Eigen::AngleAxisf init_rotation_z(predict_pose_for_ndt.yaw, Eigen::Vector3f::UnitZ());
  488. Eigen::Matrix4f init_guess = (init_translation * init_rotation_z * init_rotation_y * init_rotation_x) * tf_btol;
  489. pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  490. std::cout<<"before ndt time is "<<xTime.elapsed()<<std::endl;
  491. // std::cout<<"time is "<<xTime.elapsed()<<std::endl;
  492. align_start = std::chrono::system_clock::now();
  493. anh_gpu_ndt_ptr->align(init_guess);
  494. align_end = std::chrono::system_clock::now();
  495. std::cout<<"after ndt time is "<<xTime.elapsed()<<std::endl;
  496. has_converged = anh_gpu_ndt_ptr->hasConverged();
  497. t = anh_gpu_ndt_ptr->getFinalTransformation();
  498. iteration = anh_gpu_ndt_ptr->getFinalNumIteration();
  499. getFitnessScore_start = std::chrono::system_clock::now();
  500. fitness_score = anh_gpu_ndt_ptr->getFitnessScore();
  501. getFitnessScore_end = std::chrono::system_clock::now();
  502. trans_probability = anh_gpu_ndt_ptr->getTransformationProbability();
  503. // std::cout<<" scoure is "<<fitness_score<<std::endl;
  504. std::cout<<" iter is "<<iteration<<std::endl;
  505. t2 = t * tf_btol.inverse();
  506. getFitnessScore_time =
  507. std::chrono::duration_cast<std::chrono::microseconds>(getFitnessScore_end - getFitnessScore_start).count() /
  508. 1000.0;
  509. pthread_mutex_unlock(&mutex);
  510. tf::Matrix3x3 mat_l; // localizer
  511. mat_l.setValue(static_cast<double>(t(0, 0)), static_cast<double>(t(0, 1)), static_cast<double>(t(0, 2)),
  512. static_cast<double>(t(1, 0)), static_cast<double>(t(1, 1)), static_cast<double>(t(1, 2)),
  513. static_cast<double>(t(2, 0)), static_cast<double>(t(2, 1)), static_cast<double>(t(2, 2)));
  514. // Update localizer_pose
  515. localizer_pose.x = t(0, 3);
  516. localizer_pose.y = t(1, 3);
  517. localizer_pose.z = t(2, 3);
  518. mat_l.getRPY(localizer_pose.roll, localizer_pose.pitch, localizer_pose.yaw, 1);
  519. // std::cout<<" local pose x is "<<localizer_pose.x<<std::endl;
  520. tf::Matrix3x3 mat_b; // base_link
  521. mat_b.setValue(static_cast<double>(t2(0, 0)), static_cast<double>(t2(0, 1)), static_cast<double>(t2(0, 2)),
  522. static_cast<double>(t2(1, 0)), static_cast<double>(t2(1, 1)), static_cast<double>(t2(1, 2)),
  523. static_cast<double>(t2(2, 0)), static_cast<double>(t2(2, 1)), static_cast<double>(t2(2, 2)));
  524. // Update ndt_pose
  525. ndt_pose.x = t2(0, 3);
  526. ndt_pose.y = t2(1, 3);
  527. ndt_pose.z = t2(2, 3);
  528. // ndt_pose.x = localizer_pose.x;
  529. // ndt_pose.y = localizer_pose.y;
  530. // ndt_pose.z = localizer_pose.z;
  531. mat_b.getRPY(ndt_pose.roll, ndt_pose.pitch, ndt_pose.yaw, 1);
  532. // Calculate the difference between ndt_pose and predict_pose
  533. predict_pose_error = sqrt((ndt_pose.x - predict_pose_for_ndt.x) * (ndt_pose.x - predict_pose_for_ndt.x) +
  534. (ndt_pose.y - predict_pose_for_ndt.y) * (ndt_pose.y - predict_pose_for_ndt.y) +
  535. (ndt_pose.z - predict_pose_for_ndt.z) * (ndt_pose.z - predict_pose_for_ndt.z));
  536. // std::cout<<" pose error is "<<predict_pose_error<<std::endl;
  537. // std::cout<<"ndt pose x is "<<ndt_pose.x<<std::endl;
  538. if (predict_pose_error <= PREDICT_POSE_THRESHOLD)
  539. {
  540. use_predict_pose = 0;
  541. }
  542. else
  543. {
  544. use_predict_pose = 1;
  545. }
  546. use_predict_pose = 0;
  547. if (use_predict_pose == 0)
  548. {
  549. current_pose.x = ndt_pose.x;
  550. current_pose.y = ndt_pose.y;
  551. current_pose.z = ndt_pose.z;
  552. current_pose.roll = ndt_pose.roll;
  553. current_pose.pitch = ndt_pose.pitch;
  554. current_pose.yaw = ndt_pose.yaw;
  555. }
  556. else
  557. {
  558. current_pose.x = predict_pose_for_ndt.x;
  559. current_pose.y = predict_pose_for_ndt.y;
  560. current_pose.z = predict_pose_for_ndt.z;
  561. current_pose.roll = predict_pose_for_ndt.roll;
  562. current_pose.pitch = predict_pose_for_ndt.pitch;
  563. current_pose.yaw = predict_pose_for_ndt.yaw;
  564. }
  565. // std::cout<<" current pose x is "<<current_pose.x<<std::endl;
  566. // Compute the velocity and acceleration
  567. diff_x = current_pose.x - previous_pose.x;
  568. diff_y = current_pose.y - previous_pose.y;
  569. diff_z = current_pose.z - previous_pose.z;
  570. diff_yaw = calcDiffForRadian(current_pose.yaw, previous_pose.yaw);
  571. diff = sqrt(diff_x * diff_x + diff_y * diff_y + diff_z * diff_z);
  572. current_velocity = (diff_time > 0) ? (diff / diff_time) : 0;
  573. current_velocity_x = (diff_time > 0) ? (diff_x / diff_time) : 0;
  574. current_velocity_y = (diff_time > 0) ? (diff_y / diff_time) : 0;
  575. current_velocity_z = (diff_time > 0) ? (diff_z / diff_time) : 0;
  576. angular_velocity = (diff_time > 0) ? (diff_yaw / diff_time) : 0;
  577. current_velocity_smooth = (current_velocity + previous_velocity + previous_previous_velocity) / 3.0;
  578. if (current_velocity_smooth < 0.2)
  579. {
  580. current_velocity_smooth = 0.0;
  581. }
  582. current_accel = (diff_time > 0) ? ((current_velocity - previous_velocity) / diff_time) : 0;
  583. current_accel_x = (diff_time > 0) ? ((current_velocity_x - previous_velocity_x) / diff_time) : 0;
  584. current_accel_y = (diff_time > 0) ? ((current_velocity_y - previous_velocity_y) / diff_time) : 0;
  585. current_accel_z = (diff_time > 0) ? ((current_velocity_z - previous_velocity_z) / diff_time) : 0;
  586. // std::cout<<"fit time is "<<getFitnessScore_time<<std::endl;
  587. std::cout<<" x is "<<current_pose.x<<" y is "<<current_pose.y<<" yaw is"<<current_pose.yaw<<std::endl;
  588. // gw->Updatexyyaw(current_pose.x,current_pose.y,current_pose.yaw);
  589. std::cout<<"vel is "<<current_velocity<<std::endl;
  590. // std::cout<<" vx is "<<current_velocity_x<<" vy is "<<current_velocity_y<<std::endl;
  591. previous_pose.x = current_pose.x;
  592. previous_pose.y = current_pose.y;
  593. previous_pose.z = current_pose.z;
  594. previous_pose.roll = current_pose.roll;
  595. previous_pose.pitch = current_pose.pitch;
  596. previous_pose.yaw = current_pose.yaw;
  597. // previous_scan_time = current_scan_time;
  598. previous_previous_velocity = previous_velocity;
  599. previous_velocity = current_velocity;
  600. previous_velocity_x = current_velocity_x;
  601. previous_velocity_y = current_velocity_y;
  602. previous_velocity_z = current_velocity_z;
  603. previous_accel = current_accel;
  604. pthread_mutex_lock(&mutex_read);
  605. gindex++;
  606. glidar_pose.accel = current_accel;
  607. glidar_pose.accel_x = current_accel_x;
  608. glidar_pose.accel_y = current_accel_y;
  609. glidar_pose.accel_z = current_accel_z;
  610. glidar_pose.vel = current_velocity;
  611. glidar_pose.vel_x = current_velocity_x;
  612. glidar_pose.vel_y = current_velocity_y;
  613. glidar_pose.vel_z = current_velocity_z;
  614. glidar_pose.mpose = current_pose;
  615. pthread_mutex_unlock(&mutex_read);
  616. pthread_mutex_unlock(&mutex_pose);
  617. iv::lidar::ndtpos ndtpos;
  618. ndtpos.set_lidartime(raw_scan->header.stamp/1000);
  619. ndtpos.set_ndt_time(QDateTime::currentMSecsSinceEpoch());
  620. ndtpos.set_accel(current_accel);
  621. ndtpos.set_accel_x(current_accel_x);
  622. ndtpos.set_accel_y(current_accel_y);
  623. ndtpos.set_accel_z(current_accel_z);
  624. ndtpos.set_vel(current_velocity);
  625. ndtpos.set_vel_x(current_velocity_x);
  626. ndtpos.set_vel_y(current_velocity_y);
  627. ndtpos.set_vel_z(current_velocity_z);
  628. ndtpos.set_fitness_score(fitness_score);
  629. ndtpos.set_has_converged(has_converged);
  630. ndtpos.set_id(0);
  631. ndtpos.set_iteration(iteration);
  632. ndtpos.set_trans_probability(trans_probability);
  633. ndtpos.set_pose_pitch(current_pose.pitch);
  634. ndtpos.set_pose_roll(current_pose.roll);
  635. ndtpos.set_pose_yaw(current_pose.yaw);
  636. ndtpos.set_pose_x(current_pose.x);
  637. ndtpos.set_pose_y(current_pose.y);
  638. ndtpos.set_pose_z(current_pose.z);
  639. ndtpos.set_comp_time(xTime.elapsed());
  640. int ndatasize = ndtpos.ByteSize();
  641. char * strser = new char[ndatasize];
  642. bool bSer = ndtpos.SerializeToArray(strser,ndatasize);
  643. if(bSer)
  644. {
  645. iv::modulecomm::ModuleSendMsg(gppose,strser,ndatasize);
  646. }
  647. else
  648. {
  649. std::cout<<BOLDRED<<"ndtpos serialize error."<<RESET<<std::endl;
  650. }
  651. delete strser;
  652. }
  653. int GetPose(int & curindex,iv::lidar_pose & xlidar_pose)
  654. {
  655. pthread_mutex_lock(&mutex_read);
  656. if(curindex == gindex)
  657. {
  658. pthread_mutex_unlock(&mutex_read);
  659. return 0;
  660. }
  661. curindex = gindex;
  662. xlidar_pose = glidar_pose;
  663. pthread_mutex_unlock(&mutex_read);
  664. return 1;
  665. }
  666. void SetCurPose(double x0, double y0, double yaw0, double z0, double pitch0, double roll0)
  667. {
  668. std::cout<<"set pose"<<std::endl;
  669. pthread_mutex_lock(&mutex_pose);
  670. initial_pose.x = x0;
  671. initial_pose.y = y0;
  672. initial_pose.z = z0;
  673. initial_pose.roll = roll0;
  674. initial_pose.pitch = pitch0;
  675. initial_pose.yaw = yaw0;
  676. localizer_pose.x = initial_pose.x;
  677. localizer_pose.y = initial_pose.y;
  678. localizer_pose.z = initial_pose.z;
  679. localizer_pose.roll = initial_pose.roll;
  680. localizer_pose.pitch = initial_pose.pitch;
  681. localizer_pose.yaw = initial_pose.yaw;
  682. previous_pose.x = initial_pose.x;
  683. previous_pose.y = initial_pose.y;
  684. previous_pose.z = initial_pose.z;
  685. previous_pose.roll = initial_pose.roll;
  686. previous_pose.pitch = initial_pose.pitch;
  687. previous_pose.yaw = initial_pose.yaw;
  688. current_pose.x = initial_pose.x;
  689. current_pose.y = initial_pose.y;
  690. current_pose.z = initial_pose.z;
  691. current_pose.roll = initial_pose.roll;
  692. current_pose.pitch = initial_pose.pitch;
  693. current_pose.yaw = initial_pose.yaw;
  694. current_velocity = 0;
  695. current_velocity_x = 0;
  696. current_velocity_y = 0;
  697. current_velocity_z = 0;
  698. angular_velocity = 0;
  699. pthread_mutex_unlock(&mutex_pose);
  700. }
  701. void SetRunState(bool bRun)
  702. {
  703. std::cout<<"set state."<<std::endl;
  704. gbNDTRun = bRun;
  705. }