rslidar_test.cpp 2.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112
  1. /*
  2. * @Author: yct 18202736439@163.com
  3. * @Date: 2023-01-12 09:17:46
  4. * @LastEditors: yct 18202736439@163.com
  5. * @LastEditTime: 2023-01-12 15:12:49
  6. * @FilePath: /puai_wj_2021/tests/rslidar_test.cpp
  7. * @Description: 这是默认设置,请设置`customMade`, 打开koroFileHeader查看配置 进行设置: https://github.com/OBKoro1/koro1FileHeader/wiki/%E9%85%8D%E7%BD%AE
  8. */
  9. #include <iostream>
  10. #include <fstream>
  11. #include <glog/logging.h>
  12. GOOGLE_GLOG_DLL_DECL void shut_down_logging(const char* data, int size)
  13. {
  14. time_t tt;
  15. time( &tt );
  16. tt = tt + 8*3600; // transform the time zone
  17. tm* t= gmtime( &tt );
  18. char buf[255]={0};
  19. sprintf(buf,"./%d%02d%02d-%02d%02d%02d-dump.txt",
  20. t->tm_year + 1900,
  21. t->tm_mon + 1,
  22. t->tm_mday,
  23. t->tm_hour,
  24. t->tm_min,
  25. t->tm_sec);
  26. FILE* tp_file=fopen(buf,"w");
  27. fprintf(tp_file,data,strlen(data));
  28. fclose(tp_file);
  29. }
  30. // #include "../rslidar/rslidar_driver.h"
  31. #include "../velodyne_lidar/rs_device_bridge.h"
  32. void bridge_test()
  33. {
  34. velodyne::velodyneLidarParams params;
  35. params.set_ip("");
  36. params.set_port(2367);
  37. params.set_difop(7788);
  38. params.set_model("HELIOS16P");
  39. params.set_calibrationfile("/home/youchen/extra_space/chutian/measure/puai_wj_2021/setting/VLP16db.yaml");
  40. RS_device_bridge t_device;
  41. auto ec = t_device.init(params);
  42. if(ec != SUCCESS)
  43. {
  44. std::cout<<"init failed. "<< ec.to_string()<<std::endl;
  45. }
  46. usleep(1000 * 1000);
  47. std::mutex p_mutex;
  48. pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  49. for (size_t j = 1; j <= 300; j++)
  50. {
  51. p_cloud->clear();
  52. Error_manager ec = t_device.get_new_cloud_and_wait(&p_mutex, p_cloud, std::chrono::steady_clock::now(), 1000);
  53. if (ec == SUCCESS)
  54. {
  55. if(j % 80 == 0)
  56. {
  57. std::ofstream out((std::string("./device_point") + std::to_string(j) + std::string(".txt")).c_str());
  58. if (out.is_open())
  59. {
  60. for (size_t i = 0; i < p_cloud->size(); i++)
  61. {
  62. char buf[255] = {0};
  63. sprintf(buf, "%.3f %.3f %.3f\n", p_cloud->points[i].x, p_cloud->points[i].y, p_cloud->points[i].z);
  64. out << buf;
  65. }
  66. std::cout << "cloud written" << std::endl;
  67. out.close();
  68. }
  69. else
  70. {
  71. std::cout << "cannot open file to write cloud." << std::endl;
  72. }
  73. }
  74. }
  75. else
  76. {
  77. std::cout << "get cloud failed: "<< ec.to_string() << std::endl;
  78. }
  79. }
  80. t_device.uninit();
  81. }
  82. int main()
  83. {
  84. const char* logPath = "./log/";
  85. google::InitGoogleLogging("LidarMeasurement");
  86. google::SetStderrLogging(google::INFO);
  87. google::SetLogDestination(0, logPath);
  88. google::SetLogFilenameExtension("zxlog");
  89. google::InstallFailureSignalHandler();
  90. google::InstallFailureWriter(&shut_down_logging);
  91. FLAGS_colorlogtostderr = true; // Set log color
  92. FLAGS_logbufsecs = 0; // Set log output speed(s)
  93. FLAGS_max_log_size = 1024; // Set max log file size(GB)
  94. FLAGS_stop_logging_if_full_disk = true;
  95. // device_test();
  96. bridge_test();
  97. return 0;
  98. }