mirror of
https://git.ti.com/git/mmwave_radar/mmwave_ti_ros.git
synced 2026-05-21 09:22:15 +00:00
adjusting filters for ground
This commit is contained in:
@@ -10,8 +10,8 @@ obstacle_layer:
|
|||||||
enabled: true
|
enabled: true
|
||||||
max_obstacle_height: 2
|
max_obstacle_height: 2
|
||||||
origin_z: 0.0
|
origin_z: 0.0
|
||||||
z_resolution: 0.015
|
z_resolution: 0.05
|
||||||
z_voxels: 16
|
z_voxels: 20
|
||||||
unknown_threshold: 15
|
unknown_threshold: 15
|
||||||
mark_threshold: 2
|
mark_threshold: 2
|
||||||
combination_method: 1
|
combination_method: 1
|
||||||
@@ -24,30 +24,30 @@ obstacle_layer:
|
|||||||
data_type: PointCloud2
|
data_type: PointCloud2
|
||||||
topic: cloud_in
|
topic: cloud_in
|
||||||
marking: true
|
marking: true
|
||||||
clearing: true
|
clearing: false
|
||||||
min_obstacle_height: 0.0
|
min_obstacle_height: -3.0
|
||||||
max_obstacle_height: 2
|
max_obstacle_height: 3
|
||||||
scan1:
|
scan1:
|
||||||
data_type: PointCloud2
|
data_type: PointCloud2
|
||||||
topic: cloud_in
|
topic: cloud_in
|
||||||
marking: true
|
marking: true
|
||||||
clearing: true
|
clearing: false
|
||||||
min_obstacle_height: 0.0
|
min_obstacle_height: -3.0
|
||||||
max_obstacle_height: 2
|
max_obstacle_height: 3
|
||||||
scan2:
|
scan2:
|
||||||
data_type: PointCloud2
|
data_type: PointCloud2
|
||||||
topic: cloud_in
|
topic: cloud_in
|
||||||
marking: true
|
marking: true
|
||||||
clearing: true
|
clearing: false
|
||||||
min_obstacle_height: 0.0
|
min_obstacle_height: -3.0
|
||||||
max_obstacle_height: 2
|
max_obstacle_height: 3
|
||||||
scan3:
|
scan3:
|
||||||
data_type: PointCloud2
|
data_type: PointCloud2
|
||||||
topic: cloud_in
|
topic: cloud_in
|
||||||
marking: true
|
marking: true
|
||||||
clearing: true
|
clearing: false
|
||||||
min_obstacle_height: 0.0
|
min_obstacle_height: -3.0
|
||||||
max_obstacle_height: 2
|
max_obstacle_height: 3
|
||||||
bump:
|
bump:
|
||||||
data_type: PointCloud2
|
data_type: PointCloud2
|
||||||
topic: mobile_base/sensors/bumper_pointcloud
|
topic: mobile_base/sensors/bumper_pointcloud
|
||||||
|
|||||||
@@ -32,8 +32,8 @@
|
|||||||
<remap from="~output" to="xyz_filt_out_0" />
|
<remap from="~output" to="xyz_filt_out_0" />
|
||||||
<rosparam>
|
<rosparam>
|
||||||
filter_field_name: z
|
filter_field_name: z
|
||||||
filter_limit_min: -0.4
|
filter_limit_min: -0.5
|
||||||
filter_limit_max: 0.10
|
filter_limit_max: -0.1
|
||||||
filter_limit_negative: False
|
filter_limit_negative: False
|
||||||
</rosparam>
|
</rosparam>
|
||||||
</node>
|
</node>
|
||||||
@@ -76,8 +76,8 @@
|
|||||||
<remap from="~output" to="xyz_filt_out_1" />
|
<remap from="~output" to="xyz_filt_out_1" />
|
||||||
<rosparam>
|
<rosparam>
|
||||||
filter_field_name: z
|
filter_field_name: z
|
||||||
filter_limit_min: -0.4
|
filter_limit_min: -0.5
|
||||||
filter_limit_max: 0.10
|
filter_limit_max: -0.1
|
||||||
filter_limit_negative: False
|
filter_limit_negative: False
|
||||||
</rosparam>
|
</rosparam>
|
||||||
</node>
|
</node>
|
||||||
@@ -120,8 +120,8 @@
|
|||||||
<remap from="~output" to="xyz_filt_out_2" />
|
<remap from="~output" to="xyz_filt_out_2" />
|
||||||
<rosparam>
|
<rosparam>
|
||||||
filter_field_name: z
|
filter_field_name: z
|
||||||
filter_limit_min: -0.4
|
filter_limit_min: -0.5
|
||||||
filter_limit_max: 0.10
|
filter_limit_max: -0.1
|
||||||
filter_limit_negative: False
|
filter_limit_negative: False
|
||||||
</rosparam>
|
</rosparam>
|
||||||
</node>
|
</node>
|
||||||
@@ -164,8 +164,8 @@
|
|||||||
<remap from="~output" to="xyz_filt_out_3" />
|
<remap from="~output" to="xyz_filt_out_3" />
|
||||||
<rosparam>
|
<rosparam>
|
||||||
filter_field_name: z
|
filter_field_name: z
|
||||||
filter_limit_min: -0.4
|
filter_limit_min: -0.5
|
||||||
filter_limit_max: 0.10
|
filter_limit_max: -0.1
|
||||||
filter_limit_negative: False
|
filter_limit_negative: False
|
||||||
</rosparam>
|
</rosparam>
|
||||||
</node>
|
</node>
|
||||||
|
|||||||
Reference in New Issue
Block a user