36 #include "livox_sdk.h" 43 printf(
"livox ros driver will exit\r\n");
48 int main(
int argc,
char **argv) {
54 ros::init(argc, argv,
"livox_lidar_publisher");
60 LivoxSdkVersion _sdkversion;
61 GetLivoxSdkVersion(&_sdkversion);
63 ROS_INFO(
"The SDK version[%d.%d.%d] is too low", _sdkversion.major,
64 _sdkversion.minor, _sdkversion.patch);
72 double publish_freq = 10.0;
74 std::string frame_id =
"livox_frame";
75 bool lidar_bag =
true;
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) {
88 }
else if (publish_freq < 0.1) {
91 publish_freq = publish_freq;
95 Lddc *lddc =
new Lddc(xfer_format, multi_topic, data_src, output_type,
96 publish_freq, frame_id, lidar_bag, imu_bag);
101 ROS_INFO(
"Data Source is raw lidar.");
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());
107 std::string cmdline_bd_code;
108 livox_node.
getParam(
"cmdline_str", cmdline_bd_code);
110 std::vector<std::string> bd_code_list;
115 ret = read_lidar->InitLdsLidar(bd_code_list, user_config_path.c_str());
117 ROS_INFO(
"Init lds lidar success!");
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());
128 std::string cmdline_bd_code;
129 livox_node.
getParam(
"cmdline_str", cmdline_bd_code);
131 std::vector<std::string> bd_code_list;
136 ret = read_hub->InitLdsHub(bd_code_list, user_config_path.c_str());
143 ROS_INFO(
"Data Source is lvx file.");
145 std::string cmdline_file_path;
146 livox_node.
getParam(
"cmdline_file_path", cmdline_file_path);
150 ROS_ERROR(
"File path invalid : %s !", cmdline_file_path.c_str());
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";
162 int ret = read_lvx->
InitLdsLvx(cmdline_file_path.c_str());
164 ROS_INFO(
"Init lds lvx file success!");
bool IsFilePathValid(const char *path_str)
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
static LdsLvx * GetInstance(uint32_t interval_ms)
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)
void CreateBagFile(const std::string &file_name)
static LdsLidar * GetInstance(uint32_t interval_ms)
int main(int argc, char **argv)
void SetRosNode(ros::NodeHandle *node)
int InitLdsLvx(const char *lvx_path)
const int32_t kSdkVersionMajorLimit
bool getParam(const std::string &key, std::string &s) const
int RegisterLds(Lds *lds)
ROSCPP_DECL void shutdown()
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
void SignalHandler(int signum)
#define ROSCONSOLE_DEFAULT_NAME
void DistributeLidarData(void)
static LdsHub * GetInstance(uint32_t interval_ms)