diff --git a/config/lidar_obstacle_detector_config.yaml b/config/lidar_obstacle_detector_config.yaml index af17abc82b22984ee87f6a042e946dfb0239aae3..ea3720e89733800115091f0ee10ad7944fc8107a 100755 --- a/config/lidar_obstacle_detector_config.yaml +++ b/config/lidar_obstacle_detector_config.yaml @@ -13,5 +13,5 @@ max_ring: 10 farthest_enable: False farthest_num_rings: 9 # virtual point computation -virtual_enable: True +virtual_enable: False virtual_floor_threshold: 0.03 diff --git a/params/costmap/3d_common_params.yaml b/params/costmap/3d_common_params.yaml index 7d98df8558fe0b9b6512e172039a07cd32fad8cc..1a9b4efee9ccef9cd3563365855b87f13dc8c4b2 100755 --- a/params/costmap/3d_common_params.yaml +++ b/params/costmap/3d_common_params.yaml @@ -29,7 +29,7 @@ obstacle_layer_lidar: topic: /helena/lidar_detector/obstacles, observation_persistence: 0.0, marking: true, - clearing: true, + clearing: false, min_obstacle_height: -10.0, max_obstacle_height: 10.0, expected_update_rate: 1, @@ -54,7 +54,7 @@ obstacle_layer_camera: enabled: true track_unknown_space: true transform_tolerance: 0.2 - max_obstacle_height: 100.0 #1.0 + max_obstacle_height: 10.0 #1.0 footprint_clearing_enabled: false combination_method: 1 observation_sources: camera_marking camera_clearing @@ -66,8 +66,8 @@ obstacle_layer_camera: observation_persistence: 0.0, marking: true, clearing: false, - min_obstacle_height: -100.0, - max_obstacle_height: 100.0, + min_obstacle_height: -10.0, + max_obstacle_height: 10.0, expected_update_rate: 1, obstacle_range: 5.0, raytrace_range: 10.0 @@ -80,8 +80,8 @@ obstacle_layer_camera: observation_persistence: 0.0, marking: false, clearing: true, - min_obstacle_height: -100.0, - max_obstacle_height: 100.0, + min_obstacle_height: -10.0, + max_obstacle_height: 10.0, expected_update_rate: 1, obstacle_range: 5.0, raytrace_range: 10.0 @@ -91,7 +91,7 @@ hole_layer_near_camera: enabled: true track_unknown_space: true transform_tolerance: 0.2 - max_obstacle_height: 100.0 #1.0 + max_obstacle_height: 10.0 #1.0 footprint_clearing_enabled: false combination_method: 1 observation_sources: hole_near_marking hole_near_clearing @@ -103,8 +103,8 @@ hole_layer_near_camera: observation_persistence: 0.0, marking: true, clearing: false, - min_obstacle_height: -100.0, - max_obstacle_height: 100.0, + min_obstacle_height: -10.0, + max_obstacle_height: 10.0, expected_update_rate: 1, obstacle_range: 5.0, raytrace_range: 10.0 @@ -117,8 +117,8 @@ hole_layer_near_camera: observation_persistence: 0.0, marking: false, clearing: true, - min_obstacle_height: -100.0, - max_obstacle_height: 100.0, + min_obstacle_height: -10.0, + max_obstacle_height: 10.0, expected_update_rate: 1, obstacle_range: 5.0, raytrace_range: 10.0 @@ -128,7 +128,7 @@ hole_layer_far_camera: enabled: true track_unknown_space: true transform_tolerance: 0.2 - max_obstacle_height: 100.0 #1.0 + max_obstacle_height: 10.0 #1.0 footprint_clearing_enabled: false combination_method: 1 observation_sources: hole_far_marking hole_far_clearing @@ -140,8 +140,8 @@ hole_layer_far_camera: observation_persistence: 0.0, marking: true, clearing: false, - min_obstacle_height: -100.0, - max_obstacle_height: 100.0, + min_obstacle_height: -10.0, + max_obstacle_height: 10.0, expected_update_rate: 1, obstacle_range: 5.0, raytrace_range: 10.0 @@ -154,8 +154,8 @@ hole_layer_far_camera: observation_persistence: 0.0, marking: false, clearing: true, - min_obstacle_height: -100.0, - max_obstacle_height: 100.0, + min_obstacle_height: -10.0, + max_obstacle_height: 10.0, expected_update_rate: 1, obstacle_range: 5.0, raytrace_range: 10.0