demo_online_multi_lidars.cpp 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190
  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. #ifdef ENABLE_PCL_POINTCLOUD
  27. #include <rs_driver/msg/pcl_point_cloud_msg.hpp>
  28. #else
  29. #include <rs_driver/msg/point_cloud_msg.hpp>
  30. #endif
  31. //#define ORDERLY_EXIT
  32. typedef PointXYZI PointT;
  33. typedef PointCloudT<PointT> PointCloudMsg;
  34. using namespace robosense::lidar;
  35. class DriverClient
  36. {
  37. public:
  38. DriverClient(const std::string name)
  39. : name_(name)
  40. {
  41. }
  42. bool init(const RSDriverParam& param)
  43. {
  44. RS_INFO << "------------------------------------------------------" << RS_REND;
  45. RS_INFO << " " << name_ << RS_REND;
  46. RS_INFO << "------------------------------------------------------" << RS_REND;
  47. param.print();
  48. driver_.regPointCloudCallback (std::bind(&DriverClient::driverGetPointCloudFromCallerCallback, this),
  49. std::bind(&DriverClient::driverReturnPointCloudToCallerCallback, this, std::placeholders::_1));
  50. driver_.regExceptionCallback (std::bind(&DriverClient::exceptionCallback, this, std::placeholders::_1));
  51. if (!driver_.init(param))
  52. {
  53. RS_ERROR << name_ << ": Failed to initialize driver." << RS_REND;
  54. return false;
  55. }
  56. return true;
  57. }
  58. bool start()
  59. {
  60. to_exit_process_ = false;
  61. cloud_handle_thread_ = std::thread(std::bind(&DriverClient::processCloud, this));
  62. driver_.start();
  63. RS_DEBUG << name_ << ": Started driver." << RS_REND;
  64. return true;
  65. }
  66. void stop()
  67. {
  68. driver_.stop();
  69. to_exit_process_ = true;
  70. cloud_handle_thread_.join();
  71. }
  72. protected:
  73. std::shared_ptr<PointCloudMsg> driverGetPointCloudFromCallerCallback(void)
  74. {
  75. std::shared_ptr<PointCloudMsg> msg = free_cloud_queue_.pop();
  76. if (msg.get() != NULL)
  77. {
  78. return msg;
  79. }
  80. return std::make_shared<PointCloudMsg>();
  81. }
  82. void driverReturnPointCloudToCallerCallback(std::shared_ptr<PointCloudMsg> msg)
  83. {
  84. stuffed_cloud_queue_.push(msg);
  85. }
  86. void processCloud(void)
  87. {
  88. while (!to_exit_process_)
  89. {
  90. std::shared_ptr<PointCloudMsg> msg = stuffed_cloud_queue_.popWait();
  91. if (msg.get() == NULL)
  92. {
  93. continue;
  94. }
  95. RS_MSG << name_ << ": msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND;
  96. free_cloud_queue_.push(msg);
  97. }
  98. }
  99. void exceptionCallback(const Error& code)
  100. {
  101. RS_WARNING << name_ << ": " << code.toString() << RS_REND;
  102. }
  103. std::string name_;
  104. LidarDriver<PointCloudMsg> driver_;
  105. bool to_exit_process_;
  106. std::thread cloud_handle_thread_;
  107. SyncQueue<std::shared_ptr<PointCloudMsg>> free_cloud_queue_;
  108. SyncQueue<std::shared_ptr<PointCloudMsg>> stuffed_cloud_queue_;
  109. };
  110. int main(int argc, char* argv[])
  111. {
  112. RS_TITLE << "------------------------------------------------------" << RS_REND;
  113. RS_TITLE << " RS_Driver Core Version: v" << getDriverVersion() << RS_REND;
  114. RS_TITLE << "------------------------------------------------------" << RS_REND;
  115. RSDriverParam param_left; ///< Create a parameter object
  116. param_left.input_type = InputType::ONLINE_LIDAR;
  117. param_left.input_param.msop_port = 6004; ///< Set the lidar msop port number, the default is 6699
  118. param_left.input_param.difop_port = 7004; ///< Set the lidar difop port number, the default is 7788
  119. param_left.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct
  120. DriverClient client_left("LEFT ");
  121. if (!client_left.init(param_left)) ///< Call the init function
  122. {
  123. return -1;
  124. }
  125. RSDriverParam param_right; ///< Create a parameter object
  126. param_right.input_type = InputType::ONLINE_LIDAR;
  127. param_right.input_param.msop_port = 6005; ///< Set the lidar msop port number, the default is 6699
  128. param_right.input_param.difop_port = 7005; ///< Set the lidar difop port number, the default is 7788
  129. param_right.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct
  130. DriverClient client_right("RIGHT");
  131. if (!client_right.init(param_right)) ///< Call the init function
  132. {
  133. return -1;
  134. }
  135. client_left.start();
  136. client_right.start();
  137. #ifdef ORDERLY_EXIT
  138. std::this_thread::sleep_for(std::chrono::seconds(10));
  139. client_left.stop();
  140. client_right.stop();
  141. #else
  142. while (true)
  143. {
  144. std::this_thread::sleep_for(std::chrono::seconds(1));
  145. }
  146. #endif
  147. return 0;
  148. }