fast_lio2 released!

This commit is contained in:
xw
2021-07-04 10:17:41 -04:00
parent 6e1fa94351
commit 1087a72497
44 changed files with 7155 additions and 2973 deletions

View File

@@ -0,0 +1,28 @@
<launch>
<arg name="rviz" default="true" />
<node pkg="fast_lio" type="loam_feat_extract" name="feature_extract" output="log" />
<param name="lidar_type" type="int" value="1"/>
<param name="feature_extract_enable" type="bool" value="0"/>
<param name="blind" type="double" value="1"/>
<param name="point_filter_num" type="int" value="3"/>
<node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" required="true" launch-prefix="gdb -ex run --args">
<param name="imu_topic" type="string" value="/livox/imu" />
<param name="map_file_path" type="string" value=" " />
<param name="max_iteration" type="int" value="4" />
<param name="dense_map_enable" type="bool" value="1" />
<param name="fov_degree" type="double" value="75" />
<param name="filter_size_corner" type="double" value="0.2" />
<param name="filter_size_surf" type="double" value="0.2" />
<param name="filter_size_map" type="double" value="0.5" />
<param name="runtime_pos_log" type="bool" value="1" />
<param name="cube_side_length" type="double" value="2000" />
</node>
<!-- <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>

View File

@@ -1,41 +1,22 @@
<launch>
<!-- Launch file for Livox AVIA LiDAR -->
<arg name="rviz" default="true" />
<arg name="rviz" default="true" />
<param name="lidar_type" type="int" value="1"/>
<param name="blind" type="double" value="0.5"/>
<param name="inf_bound" type="double" value="10"/>
<param name="N_SCANS" type="int" value="6"/>
<param name="group_size" type="int" value="8"/>
<param name="disA" type="double" value="0.01"/>
<param name="disB" type="double" value="0.1"/>
<param name="p2l_ratio" type="double" value="225"/>
<param name="limit_maxmid" type="double" value="6.25"/>
<param name="limit_midmin" type="double" value="6.25"/>
<param name="limit_maxmin" type="double" value="3.24"/>
<param name="jump_up_limit" type="double" value="170.0"/>
<param name="jump_down_limit" type="double" value="8.0"/>
<param name="cos160" type="double" value="160.0"/>
<param name="edgea" type="double" value="2"/>
<param name="edgeb" type="double" value="0.1"/>
<param name="smallp_intersect" type="double" value="172.5"/>
<param name="smallp_ratio" type="double" value="1.2"/>
<rosparam command="load" file="$(find fast_lio)/config/avia.yaml" />
<param name="feature_extract_enable" type="bool" value="0"/>
<param name="point_filter_num" type="int" value="3"/>
<node pkg="fast_lio" type="loam_feat_extract" name="feature_extract" output="screen"/>
<param name="max_iteration" type="int" value="3" />
<param name="dense_map_enable" type="bool" value="1" />
<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" type="bool" value="0" />
<node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" />
<node pkg="fast_lio" type="loam_laserMapping" name="laserMapping" output="screen" required="true">
<param name="map_file_path" type="string" value=" " />
<param name="max_iteration" type="int" value="10" />
<param name="dense_map_enable" type="bool" value="true" />
<param name="fov_degree" type="double" value="75" />
<param name="filter_size_corner" type="double" value="0.3" />
<param name="filter_size_surf" type="double" value="0.2" />
<param name="filter_size_map" type="double" value="0.2" />
<param name="cube_side_length" type="double" value="10" />
</node>
<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>
<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>

View File

@@ -1,41 +0,0 @@
<launch>
<arg name="rviz" default="true" />
<param name="lidar_type" type="int" value="1"/>
<param name="blind" type="double" value="0.5"/>
<param name="inf_bound" type="double" value="10"/>
<param name="N_SCANS" type="int" value="6"/>
<param name="group_size" type="int" value="8"/>
<param name="disA" type="double" value="0.01"/>
<param name="disB" type="double" value="0.1"/>
<param name="p2l_ratio" type="double" value="225"/>
<param name="limit_maxmid" type="double" value="6.25"/>
<param name="limit_midmin" type="double" value="6.25"/>
<param name="limit_maxmin" type="double" value="3.24"/>
<param name="jump_up_limit" type="double" value="170.0"/>
<param name="jump_down_limit" type="double" value="8.0"/>
<param name="cos160" type="double" value="160.0"/>
<param name="edgea" type="double" value="2"/>
<param name="edgeb" type="double" value="0.1"/>
<param name="smallp_intersect" type="double" value="172.5"/>
<param name="smallp_ratio" type="double" value="1.2"/>
<param name="point_filter_num" type="int" value="1"/>
<node pkg="fast_lio" type="loam_feat_extract" name="feature_extract" output="screen"/>
<node pkg="fast_lio" type="loam_laserMapping" name="laserMapping" output="screen">
<param name="map_file_path" type="string" value=" " />
<param name="max_iteration" type="int" value="85" />
<param name="dense_map_enable" type="bool" value="true" />
<param name="fov_degree" type="double" value="70" />
<param name="filter_size_corner" type="double" value="0.5" />
<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="100" />
</node>
<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>

View File

@@ -0,0 +1,22 @@
<launch>
<!-- Launch file for Livox Horizon LiDAR -->
<arg name="rviz" default="true" />
<rosparam command="load" file="$(find fast_lio)/config/horizon.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="dense_map_enable" type="bool" value="0" />
<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" 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>

View File

@@ -0,0 +1,22 @@
<launch>
<!-- Launch file for ouster OS2-64 LiDAR -->
<arg name="rviz" default="true" />
<rosparam command="load" file="$(find fast_lio)/config/ouster64.yaml" />
<param name="feature_extract_enable" type="bool" value="1"/>
<param name="point_filter_num" type="int" value="3"/>
<param name="max_iteration" type="int" value="4" />
<param name="dense_map_enable" type="bool" value="1" />
<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="2000" />
<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>

View File

@@ -0,0 +1,22 @@
<launch>
<!-- Launch file for velodyne16 VLP-16 LiDAR -->
<arg name="rviz" default="true" />
<rosparam command="load" file="$(find fast_lio)/config/velody16.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="dense_map_enable" type="bool" value="1" />
<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" 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>

View File

@@ -1,26 +0,0 @@
<launch>
<arg name="rviz" default="true" />
<!-- <node pkg="fast_lio" type="imu_process" name="imu_process" output="screen"/>
<node pkg="fast_lio" type="loam_scanRegistration_horizon" name="scanRegistration_horizon" output="screen">
</node>
<node pkg="fast_lio" type="loam_laserMapping" name="laserMapping" output="screen">
<param name="map_file_path" type="string" value=" " />
<param name="filter_parameter_corner" type="double" value="0.3" />
<param name="filter_parameter_surf" type="double" value="0.2" />
</node>
<node pkg="fast_lio" type="livox_repub" name="livox_repub" output="screen" >
<remap from="/livox/lidar" to="/livox/lidar" />
</node> -->
<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>