rslidar_sdk_node.cpp 3.0 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879
  1. /******************************************************************************
  2. * Copyright 2020 RoboSense All rights reserved.
  3. * Suteng Innovation Technology Co., Ltd. www.robosense.ai
  4. * This software is provided to you directly by RoboSense and might
  5. * only be used to access RoboSense LiDAR. Any compilation,
  6. * modification, exploration, reproduction and redistribution are
  7. * restricted without RoboSense's prior consent.
  8. * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESSED OR IMPLIED
  9. * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
  10. * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
  11. * DISCLAIMED. IN NO EVENT SHALL ROBOSENSE BE LIABLE FOR ANY DIRECT,
  12. * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
  13. * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
  14. * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
  15. * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
  16. * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
  17. * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  18. * POSSIBILITY OF SUCH DAMAGE.
  19. *****************************************************************************/
  20. #include <signal.h>
  21. #include <mutex>
  22. #include <condition_variable>
  23. #include "manager/adapter_manager.hpp"
  24. using namespace robosense::lidar;
  25. std::mutex g_mtx;
  26. std::condition_variable g_cv;
  27. static void sigHandler(int sig)
  28. {
  29. RS_MSG << "RoboSense-LiDAR-Driver is stopping....." << RS_REND;
  30. #ifdef ROS_FOUND
  31. ros::shutdown();
  32. #endif
  33. g_cv.notify_all();
  34. }
  35. int main(int argc, char** argv)
  36. {
  37. signal(SIGINT, sigHandler); ///< bind ctrl+c signal with the sigHandler function
  38. RS_TITLE << "********************************************************" << RS_REND;
  39. RS_TITLE << "********** **********" << RS_REND;
  40. RS_TITLE << "********** RSLidar_SDK Version: v" << RSLIDAR_VERSION_MAJOR << "." << RSLIDAR_VERSION_MINOR << "."
  41. << RSLIDAR_VERSION_PATCH << " **********" << RS_REND;
  42. RS_TITLE << "********** **********" << RS_REND;
  43. RS_TITLE << "********************************************************" << RS_REND;
  44. std::shared_ptr<AdapterManager> demo_ptr = std::make_shared<AdapterManager>();
  45. YAML::Node config;
  46. try
  47. {
  48. config = YAML::LoadFile((std::string)PROJECT_PATH + "/config/config.yaml");
  49. }
  50. catch (...)
  51. {
  52. RS_ERROR << "Config file format wrong! Please check the format(e.g. indentation) " << RS_REND;
  53. return -1;
  54. }
  55. #ifdef ROS_FOUND ///< if ROS is found, call the ros::init function
  56. ros::init(argc, argv, "rslidar_sdk_node", ros::init_options::NoSigintHandler);
  57. #endif
  58. #ifdef ROS2_FOUND ///< if ROS2 is found, call the rclcpp::init function
  59. rclcpp::init(argc, argv);
  60. #endif
  61. demo_ptr->init(config);
  62. demo_ptr->start();
  63. RS_MSG << "RoboSense-LiDAR-Driver is running....." << RS_REND;
  64. #ifdef ROS_FOUND
  65. ros::spin();
  66. #else
  67. std::unique_lock<std::mutex> lck(g_mtx);
  68. g_cv.wait(lck);
  69. #endif
  70. return 0;
  71. }