measure_main.cpp 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127
  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.hpp"
  7. #include <glog/logging.h>
  8. #include "communication/communication_socket_base.h"
  9. #include "tool/thread_pool.h"
  10. #include "system/system_communication.h"
  11. #include "system/system_executor.h"
  12. //#define LIVOX_NUMBER 2
  13. // #define POINT_DEBUG
  14. #ifdef POINT_DEBUG
  15. std::shared_ptr<pcl::visualization::PCLVisualizer> gp_visualizer;
  16. #endif
  17. void test_whole_process() {
  18. System_executor::get_instance_references().execute_for_measure("key_for_test_only", 0,
  19. std::chrono::system_clock::now());
  20. }
  21. int main(int argc, char *argv[]) {
  22. std::cout << " measure:: " << " xxxxxxxxxxxxxxxxx " << std::endl;
  23. ZX::InitGlog("MeasureNode", ETC_PATH"/etc/MeasureNodeLog/");
  24. Error_manager t_error;
  25. Error_manager t_result;
  26. Error_manager ec;
  27. #ifdef POINT_DEBUG
  28. pcl::PointCloud<pcl::PointXYZ>::Ptr t_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  29. pcl::visualization::PCLVisualizer viewer("Viewer"); //创建viewer对象
  30. gp_visualizer = std::shared_ptr<pcl::visualization::PCLVisualizer>(&viewer);
  31. gp_visualizer->addCoordinateSystem();
  32. gp_visualizer->setBackgroundColor(0, 0, 0);
  33. gp_visualizer->initCameraParameters();
  34. gp_visualizer->addPointCloud(t_cloud, "region");
  35. #endif
  36. // 定义服务的终端id
  37. int t_terminal_id = 0;
  38. if (argc == 2) {
  39. std::cout << " huli test :::: " << " argv[1] = " << argv[1] << std::endl;
  40. t_terminal_id = atoi(argv[1]);
  41. }
  42. if (WJ_VELO == 1 || WJ_VELO == 2) {
  43. ec = Velodyne_manager::get_instance_references().velodyne_manager_init(t_terminal_id);
  44. if (ec != SUCCESS) {
  45. std::cout << "veodyne_manager = " << ec.to_string() << std::endl;
  46. std::cout << "veodyne_manager = " << Velodyne_manager::get_instance_references().check_status().to_string()
  47. << std::endl;
  48. LOG(ERROR) << "velodyne_manager init failed: " << ec.to_string();
  49. return -1;
  50. }
  51. }
  52. ec = System_executor::get_instance_references().system_executor_init(4, t_terminal_id);
  53. std::cout << "System_executor = " << System_executor::get_instance_references().get_system_executor_status()
  54. << std::endl;
  55. if (ec != SUCCESS) {
  56. LOG(ERROR) << "system executor init failed: " << ec.to_string();
  57. return -1;
  58. }
  59. ec = System_communication::get_instance_references().communication_init();
  60. if (ec != SUCCESS) {
  61. LOG(ERROR) << "system communication init failed: " << ec.to_string();
  62. return -1;
  63. }
  64. System_communication::get_instance_references().set_encapsulate_cycle_time(110);
  65. LOG(INFO) << "begain init rabbitmq.";
  66. ec = System_communication_mq::get_instance_references().rabbitmq_init();
  67. if (ec != SUCCESS) {
  68. LOG(ERROR) << "system communication mq init failed: " << ec.to_string();
  69. return -1;
  70. }
  71. System_communication_mq::get_instance_references().set_encapsulate_status_cycle_time(100);
  72. char ch = 'x';
  73. pcl::PointCloud<pcl::PointXYZ>::Ptr t_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(
  74. new pcl::PointCloud<pcl::PointXYZ>);
  75. while (ch != 'q') {
  76. #ifdef POINT_DEBUG
  77. std::map<int, Ground_region *> t_ground_region_map = Velodyne_manager::get_instance_references().get_ground_region_map();
  78. for (auto iter = t_ground_region_map.begin(); iter != t_ground_region_map.end(); ++iter)
  79. {
  80. if (iter->first == DISP_TERM_ID)
  81. {
  82. t_region_cloud->clear();
  83. // 获取区域点云
  84. iter->second->get_region_cloud(t_region_cloud, Ground_region::Region_cloud_type::filtered);
  85. // gp_visualizer->showCloud(t_region_cloud);
  86. gp_visualizer->updatePointCloud(t_region_cloud, "region");
  87. // LOG(INFO) << "pcl cloud updated." <<t_region_cloud->size();
  88. }
  89. }
  90. gp_visualizer->spinOnce();
  91. usleep(100);
  92. #else
  93. // std::cout << "please input q to quit system." << std::endl;
  94. std::cin >> ch;
  95. #endif
  96. }
  97. // 反初始化
  98. System_communication::get_instance_references().communication_uninit();
  99. System_communication_mq::get_instance_references().rabbitmq_uninit();
  100. if (WJ_VELO == 1 || WJ_VELO == 2)
  101. Velodyne_manager::get_instance_references().Velodyne_manager_uninit();
  102. System_executor::get_instance_references().system_executor_uninit();
  103. if (WJ_VELO == 0 || WJ_VELO == 2)
  104. Wanji_manager::get_instance_references().wanji_manager_uninit();
  105. return 0;
  106. }