fix the scan publish switch
parent
67f0f6b6da
commit
669eedfc7d
|
@ -21,6 +21,6 @@ mapping:
|
|||
0, 0, 1]
|
||||
|
||||
publish:
|
||||
scan_publish_en: true # 'false' will close all the point cloud output
|
||||
dense_publish_en: ture # false will low down the points number in a global-frame point clouds scan.
|
||||
scan_bodyframe_pub_en: true # output the point cloud scans in IMU-body-frame
|
||||
scan_publish_en: 1 # 'false' will close all the point cloud output
|
||||
dense_publish_en: 1 # false will low down the points number in a global-frame point clouds scan.
|
||||
scan_bodyframe_pub_en: 1 # output the point cloud scans in IMU-body-frame
|
|
@ -21,6 +21,6 @@ mapping:
|
|||
0, 0, 1]
|
||||
|
||||
publish:
|
||||
scan_publish_en: true # 'false' will close all the point cloud output
|
||||
dense_publish_en: ture # false will low down the points number in a global-frame point clouds scan.
|
||||
scan_bodyframe_pub_en: true # output the point cloud scans in IMU-body-frame
|
||||
scan_publish_en: 1 # 'false' will close all the point cloud output
|
||||
dense_publish_en: 1 # false will low down the points number in a global-frame point clouds scan.
|
||||
scan_bodyframe_pub_en: 1 # output the point cloud scans in IMU-body-frame
|
|
@ -21,6 +21,6 @@ mapping:
|
|||
0, 0, 1]
|
||||
|
||||
publish:
|
||||
scan_publish_en: true # 'false' will close all the point cloud output
|
||||
dense_publish_en: ture # false will low down the points number in a global-frame point clouds scan.
|
||||
scan_bodyframe_pub_en: true # output the point cloud scans in IMU-body-frame
|
||||
scan_publish_en: 1 # 'false' will close all the point cloud output
|
||||
dense_publish_en: 1 # false will low down the points number in a global-frame point clouds scan.
|
||||
scan_bodyframe_pub_en: 1 # output the point cloud scans in IMU-body-frame
|
|
@ -21,6 +21,6 @@ mapping:
|
|||
0, 0, 1]
|
||||
|
||||
publish:
|
||||
scan_publish_en: true # 'false' will close all the point cloud output
|
||||
dense_publish_en: ture # false will low down the points number in a global-frame point clouds scan.
|
||||
scan_bodyframe_pub_en: true # output the point cloud scans in IMU-body-frame
|
||||
scan_publish_en: 1 # 'false' will close all the point cloud output
|
||||
dense_publish_en: 1 # false will low down the points number in a global-frame point clouds scan.
|
||||
scan_bodyframe_pub_en: 1 # output the point cloud scans in IMU-body-frame
|
|
@ -6,10 +6,8 @@
|
|||
<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"/>
|
||||
<param name="point_filter_num" type="int" value="1"/>
|
||||
<param name="max_iteration" type="int" value="3" />
|
||||
<param name="scan_publish_enable" type="bool" value="1" />
|
||||
<param name="dense_publish_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" />
|
||||
|
|
|
@ -7,8 +7,6 @@
|
|||
|
||||
<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="scan_publish_enable" type="bool" value="1" />
|
||||
<param name="dense_publish_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" />
|
||||
|
|
|
@ -8,8 +8,6 @@
|
|||
<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="scan_publish_enable" type="bool" value="1" />
|
||||
<param name="dense_publish_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" />
|
||||
|
|
|
@ -8,8 +8,6 @@
|
|||
<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="scan_publish_enable" type="bool" value="1" />
|
||||
<param name="dense_publish_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" />
|
||||
|
|
|
@ -711,7 +711,7 @@ int main(int argc, char** argv)
|
|||
ros::NodeHandle nh;
|
||||
|
||||
nh.param<bool>("publish/scan_publish_en",scan_pub_en,1);
|
||||
nh.param<bool>("publish/dense_publish_en",dense_pub_en,0);
|
||||
nh.param<bool>("publish/dense_publish_en",dense_pub_en,1);
|
||||
nh.param<bool>("publish/scan_bodyframe_pub_en",scan_body_pub_en,1);
|
||||
nh.param<int>("max_iteration",NUM_MAX_ITERATIONS,4);
|
||||
nh.param<string>("map_file_path",map_file_path,"");
|
||||
|
|
Loading…
Reference in New Issue