main.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481
  1. //
  2. // Created by zx on 2020/6/18.
  3. //
  4. #include <iostream>
  5. #include "./error_code/error_code.h"
  6. #include "LogFiles.h"
  7. #include <glog/logging.h>
  8. #include "./laser/laser_manager.h"
  9. #include "./laser/Laser.h"
  10. #include "./laser/LivoxLaser.h"
  11. #include "./locate/locate_manager.h"
  12. #include "./communication/communication_socket_base.h"
  13. #include "./tool/thread_pool.h"
  14. #include "./system/system_communication.h"
  15. #include "./system/system_executor.h"
  16. #include "./wanji_lidar/wanji_lidar_device.h"
  17. #include "./tool/proto_tool.h"
  18. #include "./wanji_lidar/wanji_manager.h"
  19. #define LIVOX_NUMBER 2
  20. GOOGLE_GLOG_DLL_DECL void shut_down_logging(const char* data, int size)
  21. {
  22. time_t tt;
  23. time( &tt );
  24. tt = tt + 8*3600; // transform the time zone
  25. tm* t= gmtime( &tt );
  26. char buf[255]={0};
  27. sprintf(buf,"./%d%02d%02d-%02d%02d%02d-dump.txt",
  28. t->tm_year + 1900,
  29. t->tm_mon + 1,
  30. t->tm_mday,
  31. t->tm_hour,
  32. t->tm_min,
  33. t->tm_sec);
  34. FILE* tp_file=fopen(buf,"w");
  35. fprintf(tp_file,data,strlen(data));
  36. fclose(tp_file);
  37. }
  38. int main(int argc,char* argv[])
  39. {
  40. Error_manager t_error;
  41. Error_manager t_result ;
  42. const char* logPath = "./";
  43. google::InitGoogleLogging("LidarMeasurement");
  44. google::SetStderrLogging(google::INFO);
  45. google::SetLogDestination(0, logPath);
  46. google::SetLogFilenameExtension("zxlog");
  47. google::InstallFailureSignalHandler();
  48. google::InstallFailureWriter(&shut_down_logging);
  49. FLAGS_colorlogtostderr = true; // Set log color
  50. FLAGS_logbufsecs = 0; // Set log output speed(s)
  51. FLAGS_max_log_size = 1024; // Set max log file size(GB)
  52. FLAGS_stop_logging_if_full_disk = true;
  53. Wanji_manager::get_instance_references().wanji_manager_init();
  54. std::cout << " huli test :::: " << " wanji_manager_init = " << 1 << std::endl;
  55. /*
  56. while (1 )
  57. {
  58. char ch1 ;
  59. std::cin >> ch1 ;
  60. if (ch1 == 'b' )
  61. {
  62. break;
  63. }
  64. auto start = std::chrono::system_clock::now();
  65. Wanji_manager_task task;
  66. task.task_init(TASK_CREATED, "", NULL,
  67. std::chrono::milliseconds(1000),
  68. 0,
  69. std::chrono::system_clock::now());
  70. t_error = Wanji_manager::get_instance_references().execute_task(&task);
  71. std::cout << " huli test 123123:::: " << " t_error = " << t_error << std::endl;
  72. //判断任务是否结束, 阻塞 等待, 直到任务完成或者超时
  73. while ( task.is_task_end() == false)
  74. {
  75. if ( task.is_over_time() )
  76. {
  77. //超时处理。取消任务。
  78. Wanji_manager::get_instance_references().cancel_task(&task);
  79. task.set_task_statu(TASK_DEAD);
  80. t_error.error_manager_reset(Error_code::WANJI_LIDAR_DEVICE_TASK_OVER_TIME, Error_level::MINOR_ERROR,
  81. " locate_manager_task is_over_time ");
  82. task.set_task_error_manager(t_error);
  83. }
  84. else
  85. {
  86. //继续等待
  87. std::this_thread::sleep_for(std::chrono::microseconds(1));
  88. std::this_thread::yield();
  89. }
  90. }
  91. //提取任务单 的错误码
  92. t_error = task.get_task_error_manager();
  93. std::cout << "huli error 456456:::::::" << t_error << std::endl;
  94. std::cout << " huli test :::: " << " task.get_task_statu() = " << task.get_task_statu() << std::endl;
  95. auto end = std::chrono::system_clock::now();
  96. auto duration = std::chrono::duration_cast<std::chrono::microseconds>(end - start);
  97. std::cout << "花费了"
  98. << double(duration.count()*1000) * std::chrono::microseconds::period::num / std::chrono::microseconds::period::den << "毫秒" << std::endl;
  99. std::cout << " huli test :::: " << " std::chrono::microseconds::period::num = " << std::chrono::microseconds::period::num << std::endl;
  100. std::cout << " huli test :::: " << " std::chrono::microseconds::period::den = " << std::chrono::microseconds::period::den << std::endl;
  101. std::cout << " huli test :::: " << " duration.count() = " << duration.count() << std::endl;
  102. }
  103. // Wanji_manager::get_instance_references().wanji_manager_uninit();
  104. std::cout << " huli test :::: " << " uninit = " << 999999 << std::endl;
  105. return 0;
  106. */
  107. int t_terminal_id = 0;
  108. if ( argc == 2 )
  109. {
  110. std::cout << " huli test :::: " << " argv[1] = " << argv[1] << std::endl;
  111. t_terminal_id = atoi(argv[1]);
  112. }
  113. std::cout << " huli test :::: " << " t_terminal_id = " << t_terminal_id << std::endl;
  114. Laser_manager::get_instance_references().laser_manager_init();
  115. std::cout << "Laser_manager = " << Laser_manager::get_instance_references().get_laser_manager_status() << std::endl;
  116. Locate_manager::get_instance_references().Locate_manager_init();
  117. std::cout << "Locate_manager = " << Locate_manager::get_instance_references().get_locate_manager_status() << std::endl;
  118. System_executor::get_instance_references().system_executor_init(4, t_terminal_id);
  119. std::cout << "System_executor = " << System_executor::get_instance_references().get_system_executor_status() << std::endl;
  120. System_communication::get_instance_references().communication_init();
  121. char ch;
  122. while ( 1 )
  123. {
  124. std::cin >> ch ;
  125. if ( ch == 'b' )
  126. {
  127. break;
  128. }
  129. //第一步, 创建点云缓存, 和 指定雷达,目前就一个
  130. std::map<int,pcl::PointCloud<pcl::PointXYZ>::Ptr> point_cloud_map;
  131. std::mutex cloud_lock;
  132. pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  133. std::ifstream is;
  134. is.open("/home/huli/huli/Terminal_project/hl_measure/Terminal_process_CT/test_data/car_cloud/20200907-084334_src - Cloud.txt", std::ios::out);
  135. char t_buf[256];
  136. while ( !is.eof() )
  137. {
  138. is.getline(t_buf, 256);
  139. pcl::PointXYZ t_point;
  140. sscanf(t_buf, "%f %f %f", &t_point.x, &t_point.y, &t_point.z);
  141. t_point.x = t_point.x / 1000.0;
  142. t_point.y = t_point.y / 1000.0;
  143. t_point.z = t_point.z / 1000.0;
  144. p_cloud->push_back(t_point);
  145. }
  146. std::cout << " huli test :::: " << " p_cloud->size() = " << p_cloud->size() << std::endl;
  147. point_cloud_map[0] = p_cloud;
  148. Locate_manager_task locate_manager_task ;
  149. Common_data::Car_measure_information t_car_information_by_livox;
  150. //第五步, 创建定位模块的任务单, 并发送到 Locate_manager
  151. locate_manager_task.task_init(TASK_CREATED,"",NULL,std::chrono::milliseconds(15000),
  152. true,"/home/huli/huli/Terminal_project/hl_measure/Terminal_process_CT/data",
  153. &cloud_lock,&point_cloud_map, true );
  154. t_error = Task_command_manager::get_instance_references().execute_task(&locate_manager_task);
  155. //第六步, 等待任务单完成
  156. if ( t_error != Error_code::SUCCESS )
  157. {
  158. LOG(INFO) << " Locate_manager execute_task error ";
  159. }
  160. else
  161. {
  162. //判断任务是否结束, 阻塞 等待, 直到任务完成或者超时
  163. while ( locate_manager_task.is_task_end() == false)
  164. {
  165. if ( locate_manager_task.is_over_time() )
  166. {
  167. //超时处理。取消任务。
  168. Locate_manager::get_instance_pointer()->cancel_task();
  169. locate_manager_task.set_task_statu(TASK_DEAD);
  170. t_error.error_manager_reset(Error_code::LOCATER_MANAGER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
  171. " locate_manager_task is_over_time ");
  172. locate_manager_task.set_task_error_manager(t_error);
  173. }
  174. else
  175. {
  176. //继续等待
  177. std::this_thread::sleep_for(std::chrono::microseconds(1));
  178. std::this_thread::yield();
  179. }
  180. }
  181. //提取任务单 的错误码
  182. t_error = locate_manager_task.get_task_error_manager();
  183. if ( t_error == Error_code::SUCCESS )
  184. {
  185. t_car_information_by_livox.center_x = locate_manager_task.get_task_locate_information_ex()->locate_x;
  186. t_car_information_by_livox.center_y = locate_manager_task.get_task_locate_information_ex()->locate_y;
  187. t_car_information_by_livox.car_angle = locate_manager_task.get_task_locate_information_ex()->locate_angle;
  188. t_car_information_by_livox.car_length = locate_manager_task.get_task_locate_information_ex()->locate_length;
  189. t_car_information_by_livox.car_width = locate_manager_task.get_task_locate_information_ex()->locate_width;
  190. t_car_information_by_livox.car_height = locate_manager_task.get_task_locate_information_ex()->locate_height;
  191. t_car_information_by_livox.wheel_base = locate_manager_task.get_task_locate_information_ex()->locate_wheel_base;
  192. t_car_information_by_livox.wheel_width = locate_manager_task.get_task_locate_information_ex()->locate_wheel_width;
  193. t_car_information_by_livox.front_theta = 0;
  194. t_car_information_by_livox.correctness = true;
  195. std::cout << " huli test :::: " << " t_car_information_by_livox.center_x = " << t_car_information_by_livox.center_x << std::endl;
  196. std::cout << " huli test :::: " << " t_car_information_by_livox.center_y = " << t_car_information_by_livox.center_y << std::endl;
  197. std::cout << " huli test :::: " << " t_car_information_by_livox.car_angle = " << t_car_information_by_livox.car_angle << std::endl;
  198. std::cout << " huli test :::: " << " t_car_information_by_livox.car_length = " << t_car_information_by_livox.car_length << std::endl;
  199. std::cout << " huli test :::: " << " t_car_information_by_livox.car_width = " << t_car_information_by_livox.car_width << std::endl;
  200. std::cout << " huli test :::: " << " t_car_information_by_livox.car_height = " << t_car_information_by_livox.car_height << std::endl;
  201. std::cout << " huli test :::: " << " t_car_information_by_livox.wheel_base = " << t_car_information_by_livox.wheel_base << std::endl;
  202. std::cout << " huli test :::: " << " t_car_information_by_livox.wheel_width = " << t_car_information_by_livox.wheel_width << std::endl;
  203. std::cout << " huli test :::: " << " t_car_information_by_livox.front_theta = " << t_car_information_by_livox.front_theta << std::endl;
  204. std::cout << " huli test :::: " << " t_car_information_by_livox.correctness = " << t_car_information_by_livox.correctness << std::endl;
  205. }
  206. else
  207. {
  208. LOG(INFO) << " locate_manager_task error :::::::" << locate_manager_task.get_task_error_manager().to_string() ;
  209. }
  210. }
  211. }
  212. System_communication::get_instance_references().communication_uninit();
  213. System_executor::get_instance_references().system_executor_uninit();
  214. Locate_manager::get_instance_references().Locate_manager_uninit();
  215. Laser_manager::get_instance_references().laser_manager_uninit();
  216. return 0;
  217. LOG(INFO) << " --- main start --- " ;
  218. std::cout << "huli 101 main start!" << std::endl;
  219. std::cout << "1111111111111111111111" << std::endl;
  220. Laser_manager::get_instance_pointer()->laser_manager_init();
  221. Locate_manager::get_instance_pointer()->Locate_manager_init();
  222. Point_sift_segmentation* mp_point_sift;
  223. int point_size = 8192;
  224. int cls_num = 3;
  225. double freq = 20.0;
  226. std::string graph = "../model_param/seg_model_404500.ckpt.meta";
  227. std::string cpkt = "../model_param/seg_model_404500.ckpt";
  228. pcl::PointXYZ minp(-10000,-10000,-10000);
  229. pcl::PointXYZ maxp(10000,10000,10000);
  230. while(1)
  231. {
  232. std::cout << "huli 401 connect_laser Error_code::SUCCESS" << std::endl;
  233. std::cout << " press to start" << std::endl;
  234. char ch ;
  235. // = getchar();
  236. std::this_thread::sleep_for(std::chrono::seconds(2));
  237. std::cin >> ch ;
  238. if ( ch == 'b' )
  239. {
  240. std::cout << " end scan ------------" << std::endl;
  241. break;
  242. }
  243. std::cout << " start scan ------------" << std::endl;
  244. int n = 1;
  245. while(n)
  246. {
  247. n--;
  248. std::map<int,pcl::PointCloud<pcl::PointXYZ>::Ptr> point_cloud_map;
  249. std::mutex cloud_lock;
  250. std::vector<int> select_laser_id_vector;
  251. select_laser_id_vector.push_back(0);
  252. select_laser_id_vector.push_back(1);
  253. select_laser_id_vector.push_back(2);
  254. select_laser_id_vector.push_back(3);
  255. time_t nowTime;
  256. nowTime = time(NULL);
  257. struct tm* sysTime = localtime(&nowTime);
  258. char t_save_path[256] = { 0 };
  259. sprintf(t_save_path, "../data/%04d%02d%02d_%02d%02d%02d",
  260. sysTime->tm_year + 1900, sysTime->tm_mon + 1, sysTime->tm_mday, sysTime->tm_hour, sysTime->tm_min, sysTime->tm_sec);
  261. Laser_manager_task * laser_manager_task = new Laser_manager_task;
  262. laser_manager_task->task_init(TASK_CREATED,"",NULL,std::chrono::milliseconds(15000),
  263. true,t_save_path,&cloud_lock,&point_cloud_map,false,
  264. 1000,false,select_laser_id_vector );
  265. t_error = Task_command_manager::get_instance_references().execute_task(laser_manager_task);
  266. // tp_laser_manager->execute_task(laser_manager_task);
  267. if ( t_error != Error_code::SUCCESS )
  268. {
  269. std::cout << "huli Laser_manager:::::" << t_error.to_string() << std::endl;
  270. }
  271. else
  272. {
  273. while ( laser_manager_task->is_task_end() == false)
  274. {
  275. if ( laser_manager_task->is_over_time() )
  276. {
  277. //超时处理。取消任务。
  278. Laser_manager::get_instance_pointer()->cancel_task();
  279. laser_manager_task->set_task_statu(TASK_DEAD);
  280. t_error.error_manager_reset(Error_code::LASER_MANAGER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
  281. " laser_manager_task is_over_time ");
  282. laser_manager_task->set_task_error_manager(t_error);
  283. }
  284. else
  285. {
  286. std::this_thread::yield();
  287. }
  288. }
  289. std::cout << "huli task_error::::" << laser_manager_task->get_task_error_manager().to_string() << std::endl;
  290. }
  291. delete(laser_manager_task);
  292. std::cout << "huli laser result---------------------" << t_error.to_string() << std::endl;
  293. std::cout << "huli zczxczxczx---------------------" << t_error.to_string() << std::endl;
  294. std::cout << "huli zczxczxczx---------------------" << t_error.to_string() << std::endl;
  295. std::cout << "huli zczxczxczx---------------------" << t_error.to_string() << std::endl;
  296. /*
  297. pcl::PointCloud<pcl::PointXYZ>::Ptr scan_cloud ;
  298. scan_cloud = point_cloud_map[0];
  299. //locate
  300. pcl::getMinMax3D(*scan_cloud,minp,maxp);
  301. std::cout << "huli 112" << std::endl;
  302. mp_point_sift = new Point_sift_segmentation(point_size,cls_num,freq,minp,maxp);
  303. std::cout << t_error.to_string() << std::endl;
  304. t_error = mp_point_sift->init(graph,cpkt);
  305. std::cout << t_error.to_string() << std::endl;
  306. std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> segmentation_clouds;
  307. t_error = mp_point_sift->segmentation(scan_cloud, segmentation_clouds, true, "../data/locate_data");
  308. std::cout << t_error.to_string() << std::endl;
  309. */
  310. Locate_manager_task * locate_manager_task = new Locate_manager_task;
  311. locate_manager_task->task_init(TASK_CREATED,"",NULL,std::chrono::milliseconds(15000),
  312. true,t_save_path,&cloud_lock,&point_cloud_map, false );
  313. t_error = Task_command_manager::get_instance_references().execute_task(locate_manager_task);
  314. if ( t_error != Error_code::SUCCESS )
  315. {
  316. std::cout << "huli Locate_manager:::::" << t_error.to_string() << std::endl;
  317. }
  318. else
  319. {
  320. while ( locate_manager_task->is_task_end() == false)
  321. {
  322. if ( locate_manager_task->is_over_time() )
  323. {
  324. //超时处理。取消任务。
  325. Locate_manager::get_instance_pointer()->cancel_task();
  326. locate_manager_task->set_task_statu(TASK_DEAD);
  327. t_error.error_manager_reset(Error_code::LOCATER_MANAGER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
  328. " locate_manager_task is_over_time ");
  329. locate_manager_task->set_task_error_manager(t_error);
  330. }
  331. else
  332. {
  333. std::this_thread::yield();
  334. }
  335. }
  336. std::cout << "huli task_error:::::" << locate_manager_task->get_task_error_manager().to_string() << std::endl;
  337. std::cout << "locate_x = " << locate_manager_task->get_task_locate_information_ex()->locate_x << std::endl;
  338. std::cout << "locate_y = " << locate_manager_task->get_task_locate_information_ex()->locate_y << std::endl;
  339. std::cout << "locate_length = " << locate_manager_task->get_task_locate_information_ex()->locate_length << std::endl;
  340. std::cout << "locate_width = " << locate_manager_task->get_task_locate_information_ex()->locate_width << std::endl;
  341. std::cout << "locate_height = " << locate_manager_task->get_task_locate_information_ex()->locate_height << std::endl;
  342. std::cout << "locate_wheel_base = " << locate_manager_task->get_task_locate_information_ex()->locate_wheel_base << std::endl;
  343. std::cout << "locate_wheel_width = " << locate_manager_task->get_task_locate_information_ex()->locate_wheel_width << std::endl;
  344. std::cout << "locate_angle = " << locate_manager_task->get_task_locate_information_ex()->locate_angle << std::endl;
  345. std::cout << "locate_correct = " << locate_manager_task->get_task_locate_information_ex()->locate_correct << std::endl;
  346. }
  347. delete(locate_manager_task);
  348. std::cout << "huli locate result:::::" << t_error.to_string() << std::endl;
  349. }
  350. cout << "huli: 601 :" << t_error.to_string() << endl;
  351. std::this_thread::sleep_for(std::chrono::seconds(2));
  352. }
  353. Laser_manager::get_instance_pointer()->laser_manager_uninit();
  354. Locate_manager::get_instance_pointer()->Locate_manager_uninit();
  355. cout << "huli 1234 main end" << endl;
  356. std::this_thread::sleep_for(std::chrono::seconds(3));
  357. return 0;
  358. }