livox_ros_driver.cpp
Go to the documentation of this file.
1 //
2 // The MIT License (MIT)
3 //
4 // Copyright (c) 2019 Livox. All rights reserved.
5 //
6 // Permission is hereby granted, free of charge, to any person obtaining a copy
7 // of this software and associated documentation files (the "Software"), to deal
8 // in the Software without restriction, including without limitation the rights
9 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
10 // copies of the Software, and to permit persons to whom the Software is
11 // furnished to do so, subject to the following conditions:
12 //
13 // The above copyright notice and this permission notice shall be included in
14 // all copies or substantial portions of the Software.
15 //
16 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
17 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
18 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
19 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
20 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
21 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
22 // SOFTWARE.
23 //
24 
26 
27 #include <chrono>
28 #include <vector>
29 #include <csignal>
30 
31 #include <ros/ros.h>
32 #include "lddc.h"
33 #include "lds_hub.h"
34 #include "lds_lidar.h"
35 #include "lds_lvx.h"
36 #include "livox_sdk.h"
37 
38 using namespace livox_ros;
39 
41 
42 inline void SignalHandler(int signum) {
43  printf("livox ros driver will exit\r\n");
44  ros::shutdown();
45  exit(signum);
46 }
47 
48 int main(int argc, char **argv) {
53  }
54  ros::init(argc, argv, "livox_lidar_publisher");
55  ros::NodeHandle livox_node;
56 
57  ROS_INFO("Livox Ros Driver Version: %s", LIVOX_ROS_DRIVER_VERSION_STRING);
58  signal(SIGINT, SignalHandler);
60  LivoxSdkVersion _sdkversion;
61  GetLivoxSdkVersion(&_sdkversion);
62  if (_sdkversion.major < kSdkVersionMajorLimit) {
63  ROS_INFO("The SDK version[%d.%d.%d] is too low", _sdkversion.major,
64  _sdkversion.minor, _sdkversion.patch);
65  return 0;
66  }
67 
69  int xfer_format = kPointCloud2Msg;
70  int multi_topic = 0;
71  int data_src = kSourceRawLidar;
72  double publish_freq = 10.0; /* Hz */
73  int output_type = kOutputToRos;
74  std::string frame_id = "livox_frame";
75  bool lidar_bag = true;
76  bool imu_bag = false;
77 
78  livox_node.getParam("xfer_format", xfer_format);
79  livox_node.getParam("multi_topic", multi_topic);
80  livox_node.getParam("data_src", data_src);
81  livox_node.getParam("publish_freq", publish_freq);
82  livox_node.getParam("output_data_type", output_type);
83  livox_node.getParam("frame_id", frame_id);
84  livox_node.getParam("enable_lidar_bag", lidar_bag);
85  livox_node.getParam("enable_imu_bag", imu_bag);
86  if (publish_freq > 100.0) {
87  publish_freq = 100.0;
88  } else if (publish_freq < 0.1) {
89  publish_freq = 0.1;
90  } else {
91  publish_freq = publish_freq;
92  }
93 
95  Lddc *lddc = new Lddc(xfer_format, multi_topic, data_src, output_type,
96  publish_freq, frame_id, lidar_bag, imu_bag);
97  lddc->SetRosNode(&livox_node);
98 
99  int ret = 0;
100  if (data_src == kSourceRawLidar) {
101  ROS_INFO("Data Source is raw lidar.");
102 
103  std::string user_config_path;
104  livox_node.getParam("user_config_path", user_config_path);
105  ROS_INFO("Config file : %s", user_config_path.c_str());
106 
107  std::string cmdline_bd_code;
108  livox_node.getParam("cmdline_str", cmdline_bd_code);
109 
110  std::vector<std::string> bd_code_list;
111  ParseCommandlineInputBdCode(cmdline_bd_code.c_str(), bd_code_list);
112 
113  LdsLidar *read_lidar = LdsLidar::GetInstance(1000 / publish_freq);
114  lddc->RegisterLds(static_cast<Lds *>(read_lidar));
115  ret = read_lidar->InitLdsLidar(bd_code_list, user_config_path.c_str());
116  if (!ret) {
117  ROS_INFO("Init lds lidar success!");
118  } else {
119  ROS_ERROR("Init lds lidar fail!");
120  }
121  } else if (data_src == kSourceRawHub) {
122  ROS_INFO("Data Source is hub.");
123 
124  std::string user_config_path;
125  livox_node.getParam("user_config_path", user_config_path);
126  ROS_INFO("Config file : %s", user_config_path.c_str());
127 
128  std::string cmdline_bd_code;
129  livox_node.getParam("cmdline_str", cmdline_bd_code);
130 
131  std::vector<std::string> bd_code_list;
132  ParseCommandlineInputBdCode(cmdline_bd_code.c_str(), bd_code_list);
133 
134  LdsHub *read_hub = LdsHub::GetInstance(1000 / publish_freq);
135  lddc->RegisterLds(static_cast<Lds *>(read_hub));
136  ret = read_hub->InitLdsHub(bd_code_list, user_config_path.c_str());
137  if (!ret) {
138  ROS_INFO("Init lds hub success!");
139  } else {
140  ROS_ERROR("Init lds hub fail!");
141  }
142  } else {
143  ROS_INFO("Data Source is lvx file.");
144 
145  std::string cmdline_file_path;
146  livox_node.getParam("cmdline_file_path", cmdline_file_path);
147 
148  do {
149  if (!IsFilePathValid(cmdline_file_path.c_str())) {
150  ROS_ERROR("File path invalid : %s !", cmdline_file_path.c_str());
151  break;
152  }
153 
154  std::string rosbag_file_path;
155  int path_end_pos = cmdline_file_path.find_last_of('.');
156  rosbag_file_path = cmdline_file_path.substr(0, path_end_pos);
157  rosbag_file_path += ".bag";
158 
159  LdsLvx *read_lvx = LdsLvx::GetInstance(1000 / publish_freq);
160  lddc->RegisterLds(static_cast<Lds *>(read_lvx));
161  lddc->CreateBagFile(rosbag_file_path);
162  int ret = read_lvx->InitLdsLvx(cmdline_file_path.c_str());
163  if (!ret) {
164  ROS_INFO("Init lds lvx file success!");
165  } else {
166  ROS_ERROR("Init lds lvx file fail!");
167  }
168  } while (0);
169  }
170 
171  ros::Time::init();
172  while (ros::ok()) {
173  lddc->DistributeLidarData();
174  }
175 
176  return 0;
177 }
bool IsFilePathValid(const char *path_str)
Definition: lds.cpp:36
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
static LdsLvx * GetInstance(uint32_t interval_ms)
Definition: lds_lvx.h:43
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define LIVOX_ROS_DRIVER_VERSION_STRING
void ParseCommandlineInputBdCode(const char *cammandline_str, std::vector< std::string > &bd_code_list)
Definition: lds.cpp:128
void CreateBagFile(const std::string &file_name)
Definition: lddc.cpp:673
static LdsLidar * GetInstance(uint32_t interval_ms)
Definition: lds_lidar.h:46
#define ROS_INFO(...)
static void init()
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
void SetRosNode(ros::NodeHandle *node)
Definition: lddc.h:60
int InitLdsLvx(const char *lvx_path)
Definition: lds_lvx.cpp:66
const int32_t kSdkVersionMajorLimit
bool getParam(const std::string &key, std::string &s) const
int RegisterLds(Lds *lds)
Definition: lddc.cpp:526
ROSCPP_DECL void shutdown()
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
void SignalHandler(int signum)
signed int int32_t
Definition: stdint.h:124
#define ROS_ERROR(...)
#define ROSCONSOLE_DEFAULT_NAME
void DistributeLidarData(void)
Definition: lddc.cpp:569
static LdsHub * GetInstance(uint32_t interval_ms)
Definition: lds_hub.h:43


livox_ros_driver
Author(s): Livox Dev Team
autogenerated on Mon Mar 15 2021 02:40:46