1、驅動下載 catkin_make編譯就行
2、新建lslidar網絡
點擊網絡,選擇編輯網絡
點擊add
點擊create
Gateway使用192.168.1.1或者爲空
對比上面進行編輯並保存(激光雷達必須斷電一下,才生效)(下次插上激光雷達網線時要選擇這個網絡)
3、修改參數
<launch>
<node pkg="lslidar_c32_driver" type="lslidar_c32_driver_node" name="leishen_lslidar_c32_driver" output="screen" >
<param name="frame_id" value="laser_link"/>
<param name="device_ip" value="192.168.1.200"/>
<param name="device_port" value="2368"/>
</node>
<node pkg="lslidar_c32_decoder" type="lslidar_c32_decoder_node" name="leishen_lslidar_c32_decoder" output="screen">
<!-- <param name="child_frame_id" value="world"/> -->
<param name="child_frame_id" value="velodyne"/>
<param name="point_num" value="2000"/>
<param name="channel_num" value="0"/>
<param name="angle_disable_min" value="0"/>
<param name="angle_disable_max" value="0"/>
<param name="min_range" value="0.15"/>
<param name="max_range" value="500.0"/>
<param name="frequency" value="10.0"/>
<param name="publish_point_cloud" value="true"/>
<param name="publish_channels" value="false"/>
<remap from="lslidar_point_cloud" to="/velodyne_points" /> <!--point_raw-->
</node>
<!--node name="rviz" pkg="rviz" type="rviz" args="-d $(find lslidar_c32_decoder)/launch/lslidar_c32.rviz" output="screen"/-->
</launch>
第九行,world 改爲 velodyne(因爲ALOAM默認的velodyne)||
point_raw 改爲 velodyne_points
4、修改lslidar_c32_decoder.cpp時間戳
double timestamp = point_time;
//point_cloud->header.stamp = static_cast<uint64_t>(timestamp * 1e6);
point_cloud->header.stamp = ros::Time::now().toSec() * 1e6;
if (scan.points.size() == 0) continue;
size_t j;
VPoint point;
運行鐳神32線激光雷達
roslaunch lslidar_c32_decoder lslidar_c32.launch
運行A_LOAM
roslaunch aloam_velodyne aloam_velodyne_VLP_16.launch
LeGO_LOAM修改 run.launch : 修改爲 false
<!--- Sim Time --> **如果是仿真(如:數據集)用true,用實際的激光雷達用false**
<param name="/use_sim_time" value="false" />
運行LeGO_LOAM
roslaunch lego_loam run.launch
錄數據集對比A_LOAM LeGO_LOAM 注意事項
1、錄數據集
rosbag record -a
2、使用數據集跑 (–clock 不能丟)
rosbag play *.bag --clock
3、LeGO_LOAM運行時要區分是跑真的激光雷達還是數據集,在run.launch中要將true改爲false