-
Notifications
You must be signed in to change notification settings - Fork 2
/
livox.launch
24 lines (18 loc) · 1.03 KB
/
livox.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
<launch>
<arg name="lidar_topic" default="/livox/lidar"/>
<arg name="scan_line" default="16"/>
<arg name="PointXYZIRT" default="false"/>
<rosparam command="load" file="$(find loam_livox)/config/performance_realtime.yaml" />
<param name="common/pcd_save_dir" type="string" value="$(env HOME)/Loam_livox" />
<param name="common/log_save_dir" type="string" value="$(env HOME)/Loam_livox" />
<param name="common/loop_save_dir" type="string" value="$(env HOME)/Loam_livox" />
<param name="common/if_verbose_screen_printf" type="int" value="1"/>
<node pkg="loam_livox" type="livox_scanRegistration" name="livox_scanRegistration">
<remap from="/laser_points_0" to="$(arg lidar_topic)" />
</node>
<node pkg="loam_livox" type="livox_laserMapping" name="livox_laserMapping" output="screen" />
<arg name="rviz" default="true" />
<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find loam_livox)/rviz_cfg/rosbag_b.rviz" />
</group>
</launch>