问题
自动驾驶中常用livox-mid70激光雷达来补盲,因为其射线方向的盲区非常的小,同时价格也比较便宜。但是由于其可视角度有限,所以常用多个雷达来组合拼凑,以此达到较大范围的可视角度。
那么使用多个livox激光雷达就涉及到了设置外参,以及修改驱动文件参数,以下作出详细的展示。
一、前期准备
-
在livox官网(https://www.livoxtech.com/cn/downloads)下载
Livox Viewer 0.10.0(64bit) - Ubuntu 16.04
(ubuntu18同样可以使用) -
解压->进入文件->根据readme要求打开livox_viwer(
./livox_viewer.sh
) -
将雷达插上网线与工控机相连
-
修改雷达ip
二、配置外参
- -> 点击左上角工具栏中的三角形标定外参
- -> 点击右上角第一个符号标定外参
- -> 在下面的表中填写,填写的雷达外参,旋转以角度为单位,平移以米为单位
- -> 然后点击右下角apply即可
- -> 退出
三、驱动文件参数修改
打开多雷达的launch文件与cfg文件进行修改
{
"lidar_config": [
{
#第一个雷达配置
"broadcast_code": "3GGDJ3C00100011",
"enable_connect": true,
"return_mode": 0,
"coordinate": 0,
"imu_rate": 0,
"extrinsic_parameter_source": 1,
"enable_high_sensitivity": 0
},
{
#第二个雷达配置
"broadcast_code": "3GGDJ3C00100411",
"enable_connect": true,
"return_mode": 0,
"coordinate": 0,
"imu_rate": 0,
"extrinsic_parameter_source": 1,
"enable_high_sensitivity": 0
}
],
"timesync_config": {
"enable_timesync": false,
"device_name": "/dev/port3",
"comm_device_type": 0,
"baudrate_index": 7,
"parity_index": 0
}
}
launch文件与修改
<launch>
<arg name="lvx_file_path" default="livox_test.lvx"/>
<arg name="bd_list" default="100000000000000"/>
<arg name="xfer_format" default="0"/>
<arg name="multi_topic" default="1"/> <!-- 这里改为1 -->
<arg name="data_src" default="0"/>
<arg name="publish_freq" default="10.0"/>
<arg name="output_type" default="0"/>
<arg name="rviz_enable" default="false"/>
<arg name="rosbag_enable" default="false"/>
<arg name="cmdline_arg" default="$(arg bd_list)"/>
<arg name="msg_frame_id" default="livox_frame"/> <!-- 这里设置点云数据的坐标系 -->
<arg name="lidar_bag" default="true"/>
<arg name="imu_bag" default="true"/>
<param name="xfer_format" value="$(arg xfer_format)"/>
<param name="multi_topic" value="$(arg multi_topic)"/>
<param name="data_src" value="$(arg data_src)"/>
<param name="publish_freq" type="double" value="$(arg publish_freq)"/>
<param name="output_data_type" value="$(arg output_type)"/>
<param name="cmdline_str" type="string" value="$(arg bd_list)"/>
<param name="cmdline_file_path" type="string" value="$(arg lvx_file_path)"/>
<!-- 这里加载刚才修改的cfg文件 -->
<param name="user_config_path" type="string" value="$(find livox_ros_driver)/config/livox_lidar_config.json"/>
<param name="frame_id" type="string" value="$(arg msg_frame_id)"/>
<param name="enable_lidar_bag" type="bool" value="$(arg lidar_bag)"/>
<param name="enable_imu_bag" type="bool" value="$(arg imu_bag)"/>
<node name="livox_lidar_publisher" pkg="livox_ros_driver"
type="livox_ros_driver_node" required="true"
output="screen" args="$(arg cmdline_arg)">
<param name="multi_topic" value="$(arg multi_topic)"/>
<remap from="/livox/lidar_3GGDJ3C00100011" to="/livox/lidar_front"/> <!-- 这里可以重映射一下topic名称 -->
<remap from="/livox/lidar_3GGDJ3C00100411" to="/livox/lidar_back"/>
</node>
<group if="$(arg rviz_enable)">
<node name="rviz" pkg="rviz" type="rviz" respawn="true"
args="-d $(find livox_ros_driver)/config/display_lidar_points.rviz"/>
</group>
<group if="$(arg rosbag_enable)">
<node pkg="rosbag" type="record" name="record" output="screen"
args="-a"/>
</group>
<node pkg="tf" type="static_transform_publisher" name="base_to_livox_lidar"
args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /livox_frame 5" />
</launch>
四、时间同步配置
完成前三步后,打开launch文件的时候还会报下面的错,因为时间戳不对导致无法查看tf树。
[ WARN] [1625974729.239309016]: Lookup would require extrapolation into the past. Requested time 3834.998940030 but the earliest data is at time 1625974726.599268122, when looking up transform from frame [livox_frame] to frame [base_link]
所以还需要进行时间同步才行
具体的时间同步方法查看我之前的博客:【硬件调试-1】配置 livox-mid70 PTP时间同步
时间同步结束后打开launch文件即可。
总结
这篇博客比较详细的展示了多livox外参设置方法,其中包括livox_viewer的下载打开,ip修改,外参设置,启动文件参数修改,时间同步等多个步骤。其中第三步中,您可以根据需要,设置多话题或者单话题发布点云,我根据我的需求使用的是多话题发布。