-
Notifications
You must be signed in to change notification settings - Fork 117
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
2 changed files
with
64 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,21 @@ | ||
<launch> | ||
<!-- Launch file for ouster OS2-64 LiDAR --> | ||
|
||
<arg name="rviz" default="true" /> | ||
|
||
<rosparam command="load" file="$(find faster_lio)/config/ouster64.yaml" /> | ||
|
||
<param name="feature_extract_enable" type="bool" value="0"/> | ||
<param name="point_filter_num_" type="int" value="4"/> | ||
<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="faster_lio" type="run_mapping_online" name="laserMapping" output="screen" /> | ||
|
||
<group if="$(arg rviz)"> | ||
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find faster_lio)/rviz_cfg/loam_livox.rviz" /> | ||
</group> | ||
|
||
</launch> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,43 @@ | ||
common: | ||
lid_topic: "/os_cloud_node/points" | ||
imu_topic: "/os_cloud_node/imu" | ||
time_sync_en: false # ONLY turn on when external time synchronization is really not possible | ||
|
||
preprocess: | ||
lidar_type: 3 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, | ||
scan_line: 128 | ||
blind: 1 | ||
|
||
mapping: | ||
acc_cov: 0.1 | ||
gyr_cov: 0.1 | ||
b_acc_cov: 0.0001 | ||
b_gyr_cov: 0.0001 | ||
fov_degree: 180 | ||
det_range: 50.0 | ||
extrinsic_est_en: true # true: enable the online estimation of IMU-LiDAR extrinsic | ||
extrinsic_T: [ 0.0, 0.0, 0.0 ] | ||
extrinsic_R: [1, 0, 0, | ||
0, 1, 0, | ||
0, 0, 1] | ||
|
||
publish: | ||
path_publish_en: true | ||
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: false | ||
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. | ||
feature_extract_enable: false | ||
point_filter_num: 3 | ||
max_iteration: 3 | ||
filter_size_surf: 0.5 | ||
filter_size_map: 0.5 # 暂时未用到,代码中为0, 即倾向于将降采样后的scan中的所有点加入map | ||
cube_side_length: 1000 | ||
|
||
ivox_grid_resolution: 0.5 # default=0.2 | ||
ivox_nearby_type: 18 # 6, 18, 26 | ||
esti_plane_threshold: 0.1 # default=0.1 |