Add launch file for mid360.
							parent
							
								
									2925fef1bf
								
							
						
					
					
						commit
						478d436813
					
				|  | @ -0,0 +1,35 @@ | |||
| common: | ||||
|     lid_topic:  "/livox/lidar" | ||||
|     imu_topic:  "/livox/imu" | ||||
|     time_sync_en: false         # ONLY turn on when external time synchronization is really not possible | ||||
|     time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). | ||||
|                                   # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 | ||||
| 
 | ||||
| preprocess: | ||||
|     lidar_type: 1                # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR,  | ||||
|     scan_line: 4 | ||||
|     blind: 0.5 | ||||
| 
 | ||||
| mapping: | ||||
|     acc_cov: 0.1 | ||||
|     gyr_cov: 0.1 | ||||
|     b_acc_cov: 0.0001 | ||||
|     b_gyr_cov: 0.0001 | ||||
|     fov_degree:    360 | ||||
|     det_range:     100.0 | ||||
|     extrinsic_est_en:  false      # true: enable the online estimation of IMU-LiDAR extrinsic | ||||
|     extrinsic_T: [ -0.011, -0.02329, 0.04412 ] | ||||
|     extrinsic_R: [ 1, 0, 0, | ||||
|                    0, 1, 0, | ||||
|                    0, 0, 1] | ||||
| 
 | ||||
| publish: | ||||
|     path_en:  false | ||||
|     scan_publish_en:  true       # false: close all the point cloud output | ||||
|     dense_publish_en: true       # false: low down the points number in a global-frame point clouds scan. | ||||
|     scan_bodyframe_pub_en: true  # true: output the point cloud scans in IMU-body-frame | ||||
| 
 | ||||
| pcd_save: | ||||
|     pcd_save_en: true | ||||
|     interval: -1                 # how many LiDAR frames saved in each pcd file;  | ||||
|                                  # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. | ||||
|  | @ -0,0 +1,21 @@ | |||
| <launch> | ||||
| <!-- Launch file for Livox MID360 LiDAR --> | ||||
| 
 | ||||
| 	<arg name="rviz" default="true" /> | ||||
| 
 | ||||
| 	<rosparam command="load" file="$(find fast_lio)/config/mid360.yaml" /> | ||||
| 
 | ||||
| 	<param name="feature_extract_enable" type="bool" value="0"/> | ||||
| 	<param name="point_filter_num" type="int" value="3"/> | ||||
| 	<param name="max_iteration" type="int" value="3" /> | ||||
| 	<param name="filter_size_surf" type="double" value="0.5" /> | ||||
| 	<param name="filter_size_map" type="double" value="0.5" /> | ||||
| 	<param name="cube_side_length" type="double" value="1000" /> | ||||
| 	<param name="runtime_pos_log_enable" type="bool" value="0" /> | ||||
|     <node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" />  | ||||
| 
 | ||||
| 	<group if="$(arg rviz)"> | ||||
| 	<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find fast_lio)/rviz_cfg/loam_livox.rviz" /> | ||||
| 	</group> | ||||
| 
 | ||||
| </launch> | ||||
		Loading…
	
		Reference in New Issue