main.cpp 5.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173
  1. //
  2. // Created by zx on 2020/6/18.
  3. //
  4. #include <pcl/visualization/pcl_visualizer.h>
  5. #include <iostream>
  6. #include "./error_code/error_code.h"
  7. #include "./wanji_lidar/LogFiles.h"
  8. #include <glog/logging.h>
  9. #include "./communication/communication_socket_base.h"
  10. #include "./tool/thread_pool.h"
  11. #include "./system/system_communication.h"
  12. #include "./system/system_executor.h"
  13. // #include "./wanji_lidar/wanji_lidar_device.h"
  14. #include "./tool/proto_tool.h"
  15. #include "./wanji_lidar/wanji_manager.h"
  16. #include "./velodyne_lidar/velodyne_manager.h"
  17. #define LIVOX_NUMBER 2
  18. // #define POINT_DEBUG
  19. #ifdef POINT_DEBUG
  20. std::shared_ptr<pcl::visualization::PCLVisualizer> gp_visualizer;
  21. #endif
  22. GOOGLE_GLOG_DLL_DECL void shut_down_logging(const char* data, int size)
  23. {
  24. time_t tt;
  25. time( &tt );
  26. tt = tt + 8*3600; // transform the time zone
  27. tm* t= gmtime( &tt );
  28. char buf[255]={0};
  29. sprintf(buf,"./%d%02d%02d-%02d%02d%02d-dump.txt",
  30. t->tm_year + 1900,
  31. t->tm_mon + 1,
  32. t->tm_mday,
  33. t->tm_hour,
  34. t->tm_min,
  35. t->tm_sec);
  36. FILE* tp_file=fopen(buf,"w");
  37. fprintf(tp_file,data,strlen(data));
  38. fclose(tp_file);
  39. }
  40. void test_whole_process()
  41. {
  42. System_executor::get_instance_references().execute_for_measure("key_for_test_only", 0, std::chrono::system_clock::now());
  43. }
  44. int main(int argc,char* argv[])
  45. {
  46. Error_manager t_error;
  47. Error_manager t_result ;
  48. #ifdef POINT_DEBUG
  49. pcl::PointCloud<pcl::PointXYZ>::Ptr t_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  50. pcl::visualization::PCLVisualizer viewer("Viewer"); //创建viewer对象
  51. gp_visualizer = std::shared_ptr<pcl::visualization::PCLVisualizer>(&viewer);
  52. gp_visualizer->addCoordinateSystem();
  53. gp_visualizer->setBackgroundColor(0, 0, 0);
  54. gp_visualizer->initCameraParameters();
  55. gp_visualizer->addPointCloud(t_cloud, "region");
  56. #endif
  57. const char* logPath = "./log/";
  58. google::InitGoogleLogging("LidarMeasurement");
  59. google::SetStderrLogging(google::INFO);
  60. google::SetLogDestination(0, logPath);
  61. google::SetLogFilenameExtension("zxlog");
  62. google::InstallFailureSignalHandler();
  63. google::InstallFailureWriter(&shut_down_logging);
  64. FLAGS_colorlogtostderr = true; // Set log color
  65. FLAGS_logbufsecs = 0; // Set log output speed(s)
  66. FLAGS_max_log_size = 1024; // Set max log file size(GB)
  67. FLAGS_stop_logging_if_full_disk = true;
  68. // std::cout << " huli test :::: " << " wanji_manager_init = " << 1 << std::endl;
  69. // 定义服务的终端id
  70. int t_terminal_id = 0;
  71. if ( argc == 2 )
  72. {
  73. std::cout << " huli test :::: " << " argv[1] = " << argv[1] << std::endl;
  74. t_terminal_id = atoi(argv[1]);
  75. }
  76. std::cout << " huli test :::: " << " t_terminal_id = " << t_terminal_id << std::endl;
  77. Error_manager ec;
  78. // 初始化
  79. if(WJ_VELO == 0)
  80. {
  81. Wanji_manager::get_instance_references().wanji_manager_init(t_terminal_id);
  82. std::cout << "wanji_manager = " << Wanji_manager::get_instance_references().check_status().to_string() << std::endl;
  83. if (ec != SUCCESS)
  84. {
  85. LOG(ERROR) << "wanji_manager init failed: " << ec.to_string();
  86. return -1;
  87. }
  88. }
  89. else if(WJ_VELO == 1)
  90. {
  91. ec = Velodyne_manager::get_instance_references().velodyne_manager_init(t_terminal_id);
  92. std::cout << "veodyne_manager = " << Velodyne_manager::get_instance_references().check_status().to_string() << std::endl;
  93. if (ec != SUCCESS)
  94. {
  95. LOG(ERROR) << "velodyne_manager init failed: " << ec.to_string();
  96. return -1;
  97. }
  98. }
  99. ec = System_executor::get_instance_references().system_executor_init(4, t_terminal_id);
  100. std::cout << "System_executor = " << System_executor::get_instance_references().get_system_executor_status() << std::endl;
  101. if(ec != SUCCESS)
  102. {
  103. LOG(ERROR) << "system executor init failed: " << ec.to_string();
  104. return -1;
  105. }
  106. // usleep(1000 * 500);
  107. ec = System_communication::get_instance_references().communication_init();
  108. if(ec != SUCCESS)
  109. {
  110. LOG(ERROR) << "system communication init failed: " << ec.to_string();
  111. return -1;
  112. }
  113. System_communication::get_instance_references().set_encapsulate_cycle_time(110);
  114. // prev_test_pred_task();
  115. // test_whole_process();
  116. // usleep(1000*5000);
  117. char ch='x' ;
  118. pcl::PointCloud<pcl::PointXYZ>::Ptr t_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  119. while(ch != 'q') {
  120. #ifdef POINT_DEBUG
  121. std::map<int, Ground_region *> t_ground_region_map = Velodyne_manager::get_instance_references().get_ground_region_map();
  122. for (auto iter = t_ground_region_map.begin(); iter != t_ground_region_map.end(); ++iter)
  123. {
  124. if (iter->first == DISP_TERM_ID)
  125. {
  126. t_region_cloud->clear();
  127. // 获取区域点云
  128. iter->second->get_region_cloud(t_region_cloud, Ground_region::Region_cloud_type::filtered);
  129. // gp_visualizer->showCloud(t_region_cloud);
  130. gp_visualizer->updatePointCloud(t_region_cloud, "region");
  131. // LOG(INFO) << "pcl cloud updated." <<t_region_cloud->size();
  132. }
  133. }
  134. gp_visualizer->spinOnce();
  135. usleep(100);
  136. #else
  137. std::cout << "please input q to quit system." << std::endl;
  138. std::cin >> ch;
  139. #endif
  140. }
  141. // 反初始化
  142. System_communication::get_instance_references().communication_uninit();
  143. System_executor::get_instance_references().system_executor_uninit();
  144. if(WJ_VELO == 0)
  145. Wanji_manager::get_instance_references().wanji_manager_uninit();
  146. else if(WJ_VELO == 1)
  147. Velodyne_manager::get_instance_references().Velodyne_manager_uninit();
  148. return 0;
  149. }