rs_driver_viewer.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296
  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<PointCloudMsg> g_pointcloud;
  33. std::shared_ptr<PCLVisualizer> pcl_viewer;
  34. std::mutex mex_viewer;
  35. bool checkKeywordExist(int argc, const char* const* argv, const char* str)
  36. {
  37. for (int i = 1; i < argc; i++)
  38. {
  39. if (strcmp(argv[i], str) == 0)
  40. {
  41. return true;
  42. }
  43. }
  44. return false;
  45. }
  46. bool parseArgument(int argc, const char* const* argv, const char* str, std::string& val)
  47. {
  48. int index = -1;
  49. for (int i = 1; i < argc; i++)
  50. {
  51. if (strcmp(argv[i], str) == 0)
  52. {
  53. index = i + 1;
  54. }
  55. }
  56. if (index > 0 && index < argc)
  57. {
  58. val = argv[index];
  59. return true;
  60. }
  61. return false;
  62. }
  63. void parseParam(int argc, char* argv[], RSDriverParam& param)
  64. {
  65. param.decoder_param.wait_for_difop = false;
  66. std::string result_str;
  67. // input param
  68. parseArgument(argc, argv, "-pcap", param.input_param.pcap_path);
  69. if (param.input_param.pcap_path.empty())
  70. {
  71. param.input_type = InputType::ONLINE_LIDAR;
  72. }
  73. else
  74. {
  75. param.input_type = InputType::PCAP_FILE;
  76. }
  77. parseArgument(argc, argv, "-host", param.input_param.host_address);
  78. parseArgument(argc, argv, "-group", param.input_param.group_address);
  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. // decoder param
  88. if (parseArgument(argc, argv, "-type", result_str))
  89. {
  90. param.lidar_type = strToLidarType(result_str);
  91. }
  92. if (parseArgument(argc, argv, "-x", result_str))
  93. {
  94. param.decoder_param.transform_param.x = std::stof(result_str);
  95. }
  96. if (parseArgument(argc, argv, "-y", result_str))
  97. {
  98. param.decoder_param.transform_param.y = std::stof(result_str);
  99. }
  100. if (parseArgument(argc, argv, "-z", result_str))
  101. {
  102. param.decoder_param.transform_param.z = std::stof(result_str);
  103. }
  104. if (parseArgument(argc, argv, "-roll", result_str))
  105. {
  106. param.decoder_param.transform_param.roll = std::stof(result_str);
  107. }
  108. if (parseArgument(argc, argv, "-pitch", result_str))
  109. {
  110. param.decoder_param.transform_param.pitch = std::stof(result_str);
  111. }
  112. if (parseArgument(argc, argv, "-yaw", result_str))
  113. {
  114. param.decoder_param.transform_param.yaw = std::stof(result_str);
  115. }
  116. }
  117. void printHelpMenu()
  118. {
  119. RS_MSG << "Argument list: " << RS_REND;
  120. RS_MSG << " -msop = LiDAR msop port number,the default value is 6699" << RS_REND;
  121. RS_MSG << " -difop = LiDAR difop port number,the default value is 7788" << RS_REND;
  122. RS_MSG << " -host = LiDAR destination address." << RS_REND;
  123. RS_MSG << " -group = LiDAR destination group address." << RS_REND;
  124. RS_MSG << " -pcap = The path of the pcap file, if this argument is set, the driver "
  125. "will work in off-line mode and read the pcap file. Otherwise the driver work in online mode." << RS_REND;
  126. RS_MSG << " -type = LiDAR type(RS16, RS32, RSBP, RSHELIOS, RS128, RS80, RSM1), the default value is RS16"
  127. << RS_REND;
  128. RS_MSG << " -x = Transformation parameter, unit: m " << RS_REND;
  129. RS_MSG << " -y = Transformation parameter, unit: m " << RS_REND;
  130. RS_MSG << " -z = Transformation parameter, unit: m " << RS_REND;
  131. RS_MSG << " -roll = Transformation parameter, unit: radian " << RS_REND;
  132. RS_MSG << " -pitch = Transformation parameter, unit: radian " << RS_REND;
  133. RS_MSG << " -yaw = Transformation parameter, unit: radian " << RS_REND;
  134. }
  135. void printParam(const RSDriverParam& param)
  136. {
  137. if (param.input_type == InputType::PCAP_FILE)
  138. {
  139. RS_INFOL << "Working mode: ";
  140. RS_INFO << "Offline Pcap " << RS_REND;
  141. RS_INFOL << "Pcap Path: ";
  142. RS_INFO << param.input_param.pcap_path << RS_REND;
  143. }
  144. else
  145. {
  146. RS_INFOL << "Working mode: ";
  147. RS_INFO << "Online LiDAR " << RS_REND;
  148. }
  149. RS_INFOL << "MSOP Port: ";
  150. RS_INFO << param.input_param.msop_port << RS_REND;
  151. RS_INFOL << "DIFOP Port: ";
  152. RS_INFO << param.input_param.difop_port << RS_REND;
  153. RS_INFOL << "Host Adress: ";
  154. RS_INFO << param.input_param.host_address << RS_REND;
  155. RS_INFOL << "Group Adress: ";
  156. RS_INFO << param.input_param.group_address << RS_REND;
  157. RS_INFOL << "LiDAR Type: ";
  158. RS_INFO << lidarTypeToStr(param.lidar_type) << RS_REND;
  159. RS_INFOL << "Transformation Parameters (x, y, z, roll, pitch, yaw): " << RS_REND;
  160. RS_INFOL << "x: ";
  161. RS_INFO << std::fixed << param.decoder_param.transform_param.x << RS_REND;
  162. RS_INFOL << "y: ";
  163. RS_INFO << std::fixed << param.decoder_param.transform_param.y << RS_REND;
  164. RS_INFOL << "z: ";
  165. RS_INFO << std::fixed << param.decoder_param.transform_param.z << RS_REND;
  166. RS_INFOL << "roll: ";
  167. RS_INFO << std::fixed << param.decoder_param.transform_param.roll << RS_REND;
  168. RS_INFOL << "pitch: ";
  169. RS_INFO << std::fixed << param.decoder_param.transform_param.pitch << RS_REND;
  170. RS_INFOL << "yaw: ";
  171. RS_INFO << std::fixed << param.decoder_param.transform_param.yaw << RS_REND;
  172. }
  173. std::shared_ptr<PointCloudMsg> pointCloudGetCallback(void)
  174. {
  175. return g_pointcloud;
  176. }
  177. /**
  178. * @brief The point cloud callback function. This function will be registered to lidar driver.
  179. * When the point cloud message is ready, driver can send out messages through this function.
  180. * @param msg The lidar point cloud message.
  181. */
  182. void pointCloudPutCallback(std::shared_ptr<PointCloudMsg> msg)
  183. {
  184. /* Note: Please do not put time-consuming operations in the callback function! */
  185. /* Make a copy of the message and process it in another thread is recommended*/
  186. pcl::PointCloud<pcl::PointXYZI>::Ptr pcl_pointcloud(new pcl::PointCloud<pcl::PointXYZI>);
  187. pcl_pointcloud->points.assign(msg->points.begin(), msg->points.end());
  188. pcl_pointcloud->height = msg->height;
  189. pcl_pointcloud->width = msg->width;
  190. pcl_pointcloud->is_dense = msg->is_dense;
  191. PointCloudColorHandlerGenericField<pcl::PointXYZI> point_color_handle(pcl_pointcloud, "intensity");
  192. {
  193. const std::lock_guard<std::mutex> lock(mex_viewer);
  194. pcl_viewer->updatePointCloud<pcl::PointXYZI>(pcl_pointcloud, point_color_handle, "rslidar");
  195. }
  196. }
  197. /**
  198. * @brief The exception callback function. This function will be registered to lidar driver.
  199. * @param code The error code struct.
  200. */
  201. void exceptionCallback(const Error& code)
  202. {
  203. /* Note: Please do not put time-consuming operations in the callback function! */
  204. /* Make a copy of the error message and process it in another thread is recommended*/
  205. RS_WARNING << code.toString() << RS_REND;
  206. }
  207. int main(int argc, char* argv[])
  208. {
  209. RS_TITLE << "------------------------------------------------------" << RS_REND;
  210. RS_TITLE << " RS_Driver Viewer Version: v" << getDriverVersion() << RS_REND;
  211. RS_TITLE << "------------------------------------------------------" << RS_REND;
  212. if (argc < 2)
  213. {
  214. RS_INFOL << "Use 'rs_driver_viewer -h/--help' to check the argument menu..." << RS_REND;
  215. }
  216. if (checkKeywordExist(argc, argv, "-h") || checkKeywordExist(argc, argv, "--help"))
  217. {
  218. printHelpMenu();
  219. return 0;
  220. }
  221. RSDriverParam param; ///< Create a parameter object
  222. parseParam(argc, argv, param);
  223. printParam(param);
  224. g_pointcloud = std::make_shared<PointCloudMsg>();
  225. pcl_viewer = std::make_shared<PCLVisualizer>("RSPointCloudViewer");
  226. pcl_viewer->setBackgroundColor(0.0, 0.0, 0.0);
  227. pcl_viewer->addCoordinateSystem(1.0);
  228. pcl::PointCloud<pcl::PointXYZI>::Ptr pcl_pointcloud(new pcl::PointCloud<pcl::PointXYZI>);
  229. pcl_viewer->addPointCloud<pcl::PointXYZI>(pcl_pointcloud, "rslidar");
  230. pcl_viewer->setPointCloudRenderingProperties(PCL_VISUALIZER_POINT_SIZE, 2, "rslidar");
  231. LidarDriver<PointCloudMsg> driver; ///< Declare the driver object
  232. driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback
  233. driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback
  234. if (!driver.init(param)) ///< Call the init function
  235. {
  236. RS_ERROR << "Driver Initialize Error..." << RS_REND;
  237. return -1;
  238. }
  239. driver.start(); ///< The driver thread will start
  240. RS_INFO << "RoboSense Lidar-Driver Viewer start......" << RS_REND;
  241. while (!pcl_viewer->wasStopped())
  242. {
  243. {
  244. const std::lock_guard<std::mutex> lock(mex_viewer);
  245. pcl_viewer->spinOnce();
  246. }
  247. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  248. }
  249. return 0;
  250. }