rs_driver_viewer.cpp 8.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285
  1. /*********************************************************************************************************************
  2. Copyright (c) 2020 RoboSense
  3. All rights reserved
  4. By downloading, copying, installing or using the software you agree to this license. If you do not agree to this
  5. license, do not download, install, copy or use the software.
  6. License Agreement
  7. For RoboSense LiDAR SDK Library
  8. (3-clause BSD License)
  9. Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
  10. following conditions are met:
  11. 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following
  12. disclaimer.
  13. 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following
  14. disclaimer in the documentation and/or other materials provided with the distribution.
  15. 3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used
  16. to endorse or promote products derived from this software without specific prior written permission.
  17. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
  18. INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
  19. DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
  20. SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
  21. SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
  22. WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
  23. THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  24. *********************************************************************************************************************/
  25. #include <rs_driver/api/lidar_driver.hpp>
  26. #include <rs_driver/msg/pcl_point_cloud_msg.hpp>
  27. #include <pcl/point_types.h>
  28. #include <pcl/visualization/pcl_visualizer.h>
  29. using namespace robosense::lidar;
  30. using namespace pcl::visualization;
  31. typedef PointCloudT<PointXYZI> PointCloudMsg;
  32. std::shared_ptr<PCLVisualizer> pcl_viewer;
  33. std::mutex mtx_viewer;
  34. SyncQueue<std::shared_ptr<PointCloudMsg>> free_cloud_queue;
  35. SyncQueue<std::shared_ptr<PointCloudMsg>> stuffed_cloud_queue;
  36. bool checkKeywordExist(int argc, const char* const* argv, const char* str)
  37. {
  38. for (int i = 1; i < argc; i++)
  39. {
  40. if (strcmp(argv[i], str) == 0)
  41. {
  42. return true;
  43. }
  44. }
  45. return false;
  46. }
  47. bool parseArgument(int argc, const char* const* argv, const char* str, std::string& val)
  48. {
  49. int index = -1;
  50. for (int i = 1; i < argc; i++)
  51. {
  52. if (strcmp(argv[i], str) == 0)
  53. {
  54. index = i + 1;
  55. }
  56. }
  57. if (index > 0 && index < argc)
  58. {
  59. val = argv[index];
  60. return true;
  61. }
  62. return false;
  63. }
  64. void parseParam(int argc, char* argv[], RSDriverParam& param)
  65. {
  66. std::string result_str;
  67. //
  68. // input param
  69. //
  70. parseArgument(argc, argv, "-pcap", param.input_param.pcap_path);
  71. if (param.input_param.pcap_path.empty())
  72. {
  73. param.input_type = InputType::ONLINE_LIDAR;
  74. }
  75. else
  76. {
  77. param.input_type = InputType::PCAP_FILE;
  78. }
  79. if (parseArgument(argc, argv, "-msop", result_str))
  80. {
  81. param.input_param.msop_port = std::stoi(result_str);
  82. }
  83. if (parseArgument(argc, argv, "-difop", result_str))
  84. {
  85. param.input_param.difop_port = std::stoi(result_str);
  86. }
  87. parseArgument(argc, argv, "-group", param.input_param.group_address);
  88. parseArgument(argc, argv, "-host", param.input_param.host_address);
  89. //
  90. // decoder param
  91. //
  92. if (parseArgument(argc, argv, "-type", result_str))
  93. {
  94. param.lidar_type = strToLidarType(result_str);
  95. }
  96. param.decoder_param.wait_for_difop = false;
  97. if (parseArgument(argc, argv, "-x", result_str))
  98. {
  99. param.decoder_param.transform_param.x = std::stof(result_str);
  100. }
  101. if (parseArgument(argc, argv, "-y", result_str))
  102. {
  103. param.decoder_param.transform_param.y = std::stof(result_str);
  104. }
  105. if (parseArgument(argc, argv, "-z", result_str))
  106. {
  107. param.decoder_param.transform_param.z = std::stof(result_str);
  108. }
  109. if (parseArgument(argc, argv, "-roll", result_str))
  110. {
  111. param.decoder_param.transform_param.roll = std::stof(result_str);
  112. }
  113. if (parseArgument(argc, argv, "-pitch", result_str))
  114. {
  115. param.decoder_param.transform_param.pitch = std::stof(result_str);
  116. }
  117. if (parseArgument(argc, argv, "-yaw", result_str))
  118. {
  119. param.decoder_param.transform_param.yaw = std::stof(result_str);
  120. }
  121. }
  122. void printHelpMenu()
  123. {
  124. RS_MSG << "Arguments: " << RS_REND;
  125. RS_MSG << " -type = LiDAR type(RS16, RS32, RSBP, RSHELIOS, RS128, RS80, RSM1)" << RS_REND;
  126. RS_MSG << " -pcap = The path of the pcap file, off-line mode if it is true, else online mode." << RS_REND;
  127. RS_MSG << " -msop = LiDAR msop port number,the default value is 6699" << RS_REND;
  128. RS_MSG << " -difop = LiDAR difop port number,the default value is 7788" << RS_REND;
  129. RS_MSG << " -group = LiDAR destination group address if multi-cast mode." << RS_REND;
  130. RS_MSG << " -host = Host address." << RS_REND;
  131. RS_MSG << " -x = Transformation parameter, unit: m " << RS_REND;
  132. RS_MSG << " -y = Transformation parameter, unit: m " << RS_REND;
  133. RS_MSG << " -z = Transformation parameter, unit: m " << RS_REND;
  134. RS_MSG << " -roll = Transformation parameter, unit: radian " << RS_REND;
  135. RS_MSG << " -pitch = Transformation parameter, unit: radian " << RS_REND;
  136. RS_MSG << " -yaw = Transformation parameter, unit: radian " << RS_REND;
  137. }
  138. void exceptionCallback(const Error& code)
  139. {
  140. RS_WARNING << code.toString() << RS_REND;
  141. }
  142. std::shared_ptr<PointCloudMsg> pointCloudGetCallback(void)
  143. {
  144. std::shared_ptr<PointCloudMsg> msg = free_cloud_queue.pop();
  145. if (msg.get() != NULL)
  146. {
  147. return msg;
  148. }
  149. return std::make_shared<PointCloudMsg>();
  150. }
  151. void pointCloudPutCallback(std::shared_ptr<PointCloudMsg> msg)
  152. {
  153. stuffed_cloud_queue.push(msg);
  154. }
  155. bool to_exit_process = false;
  156. void processCloud(void)
  157. {
  158. while (!to_exit_process)
  159. {
  160. std::shared_ptr<PointCloudMsg> msg = stuffed_cloud_queue.popWait();
  161. if (msg.get() == NULL)
  162. {
  163. continue;
  164. }
  165. //
  166. // show the point cloud
  167. //
  168. pcl::PointCloud<pcl::PointXYZI>::Ptr pcl_pointcloud(new pcl::PointCloud<pcl::PointXYZI>);
  169. pcl_pointcloud->points.swap(msg->points);
  170. pcl_pointcloud->height = msg->height;
  171. pcl_pointcloud->width = msg->width;
  172. pcl_pointcloud->is_dense = msg->is_dense;
  173. PointCloudColorHandlerGenericField<pcl::PointXYZI> point_color_handle(pcl_pointcloud, "intensity");
  174. {
  175. const std::lock_guard<std::mutex> lock(mtx_viewer);
  176. pcl_viewer->updatePointCloud<pcl::PointXYZI>(pcl_pointcloud, point_color_handle, "rslidar");
  177. }
  178. free_cloud_queue.push(msg);
  179. }
  180. }
  181. int main(int argc, char* argv[])
  182. {
  183. RS_TITLE << "------------------------------------------------------" << RS_REND;
  184. RS_TITLE << " RS_Driver Viewer Version: v" << getDriverVersion() << RS_REND;
  185. RS_TITLE << "------------------------------------------------------" << RS_REND;
  186. if (argc < 2)
  187. {
  188. printHelpMenu();
  189. return 0;
  190. }
  191. if (checkKeywordExist(argc, argv, "-h") || checkKeywordExist(argc, argv, "--help"))
  192. {
  193. printHelpMenu();
  194. return 0;
  195. }
  196. std::thread cloud_handle_thread = std::thread(processCloud);
  197. RSDriverParam param;
  198. parseParam(argc, argv, param);
  199. param.print();
  200. pcl_viewer = std::make_shared<PCLVisualizer>("RSPointCloudViewer");
  201. pcl_viewer->setBackgroundColor(0.0, 0.0, 0.0);
  202. pcl_viewer->addCoordinateSystem(1.0);
  203. pcl::PointCloud<pcl::PointXYZI>::Ptr pcl_pointcloud(new pcl::PointCloud<pcl::PointXYZI>);
  204. pcl_viewer->addPointCloud<pcl::PointXYZI>(pcl_pointcloud, "rslidar");
  205. pcl_viewer->setPointCloudRenderingProperties(PCL_VISUALIZER_POINT_SIZE, 2, "rslidar");
  206. LidarDriver<PointCloudMsg> driver;
  207. driver.regExceptionCallback(exceptionCallback);
  208. driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback);
  209. if (!driver.init(param))
  210. {
  211. RS_ERROR << "Driver Initialize Error..." << RS_REND;
  212. return -1;
  213. }
  214. RS_INFO << "RoboSense Lidar-Driver Viewer start......" << RS_REND;
  215. driver.start();
  216. while (!pcl_viewer->wasStopped())
  217. {
  218. {
  219. const std::lock_guard<std::mutex> lock(mtx_viewer);
  220. pcl_viewer->spinOnce();
  221. }
  222. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  223. }
  224. driver.stop();
  225. to_exit_process = true;
  226. cloud_handle_thread.join();
  227. return 0;
  228. }