diff --git a/params/costmap/3d_common_params.yaml b/params/costmap/3d_common_params.yaml new file mode 100755 index 0000000000000000000000000000000000000000..162831ec14c05f3dcf3c27145980d322ddc2f192 --- /dev/null +++ b/params/costmap/3d_common_params.yaml @@ -0,0 +1,142 @@ +# footprint parameters +footprint: [[0.3, 0.3], [0.3, -0.3], [-0.3,-0.3 ], [-0.3, 0.3]] +#robot_radius: 0.3 +footprint_padding: 0.01 +footprint_topic: /ana/footprint +published_footprint_topic: false + +robot_base_frame: /ana/base_footprint +track_unknown_space: false +always_send_full_costmap: false +transform_tolerance: 1.0 +width: 10.0 +height: 10.0 +resolution: 0.1 +origin_x: 0.0 +origin_y: 0.0 + +obstacle_layer_lidar: + enabled: true + track_unknown_space: true + transform_tolerance: 0.2 + max_obstacle_height: 10.0 + footprint_clearing_enabled: false + combination_method: 1 + observation_sources: lidar_marking + lidar_marking: { + sensor_frame: /ana/base_footprint, + data_type: LaserScan, + topic: /ana/lidar_detector/scan_out, + observation_persistence: 0.0, + marking: true, + clearing: true, + min_obstacle_height: -10.0, + max_obstacle_height: 10.0, + expected_update_rate: 1, + obstacle_range: 5.0, + raytrace_range: 200.0 + } + +obstacle_layer_camera: + enabled: true + track_unknown_space: true + transform_tolerance: 0.2 + max_obstacle_height: 100.0 #1.0 + footprint_clearing_enabled: false + combination_method: 1 + observation_sources: camera_marking + + camera_marking: { + sensor_frame: /ana/base_footprint, + data_type: PointCloud, + topic: /ana/obstacle_detection_normals/obstacles, + observation_persistence: 0.0, + marking: true, + clearing: true, + min_obstacle_height: -100.0, + max_obstacle_height: 100.0, + expected_update_rate: 1, + obstacle_range: 5.0, + raytrace_range: 10.0 + } + +hole_layer_near_camera: + enabled: true + track_unknown_space: true + transform_tolerance: 0.2 + max_obstacle_height: 100.0 #1.0 + footprint_clearing_enabled: false + combination_method: 1 + observation_sources: hole_near_marking hole_near_clearing + + hole_near_marking: { + sensor_frame: /ana/base_footprint, + data_type: PointCloud2, + topic: /ana/near_hole_detection/hole_obstacle, + observation_persistence: 0.0, + marking: true, + clearing: false, + min_obstacle_height: -100.0, + max_obstacle_height: 100.0, + expected_update_rate: 1, + obstacle_range: 5.0, + raytrace_range: 10.0 + } + + hole_near_clearing: { + sensor_frame: /ana/base_footprint, + data_type: PointCloud2, + topic: /ana/near_hole_detection/hole_zone, + observation_persistence: 0.0, + marking: false, + clearing: true, + min_obstacle_height: -100.0, + max_obstacle_height: 100.0, + expected_update_rate: 1, + obstacle_range: 5.0, + raytrace_range: 10.0 + } + +hole_layer_far_camera: + enabled: true + track_unknown_space: true + transform_tolerance: 0.2 + max_obstacle_height: 100.0 #1.0 + footprint_clearing_enabled: false + combination_method: 1 + observation_sources: hole_far_marking hole_far_clearing + + hole_far_marking: { + sensor_frame: /ana/base_footprint, + data_type: PointCloud2, + topic: /ana/far_hole_detection/hole_obstacle, + observation_persistence: 0.0, + marking: true, + clearing: false, + min_obstacle_height: -100.0, + max_obstacle_height: 100.0, + expected_update_rate: 1, + obstacle_range: 5.0, + raytrace_range: 10.0 + } + + hole_far_clearing: { + sensor_frame: /ana/base_footprint, + data_type: PointCloud2, + topic: /ana/far_hole_detection/hole_zone, + observation_persistence: 0.0, + marking: false, + clearing: true, + min_obstacle_height: -100.0, + max_obstacle_height: 100.0, + expected_update_rate: 1, + obstacle_range: 5.0, + raytrace_range: 10.0 + } + +inflation_layer: + enabled: true + inflate_unknown: false + inflation_radius: 2.0 + cost_scaling_factor: 1.8 + inflation_radius: 1.0 diff --git a/params/costmap/3d_local_params.yaml b/params/costmap/3d_local_params.yaml new file mode 100755 index 0000000000000000000000000000000000000000..3a1d990ad00d82e789e25d59fbc2925f002dae1f --- /dev/null +++ b/params/costmap/3d_local_params.yaml @@ -0,0 +1,20 @@ +#local_costmap: ###namespace added when loading parameters in move_base.launch +global_frame: ana/odom +update_frequency: 5.0 +publish_frequency: 2.0 +rolling_window: true +width: 10.0 +height: 10.0 +resolution: 0.1 +#origin_x: 0.0 +#origin_y: 0.0 + +#costmap plugins +plugins: + - {name: obstacle_layer_lidar, type: "costmap_2d::ObstacleLayer"} + - {name: obstacle_layer_camera, type: "costmap_2d::ObstacleLayer"} + - {name: hole_layer_near_camera, type: "costmap_2d::ObstacleLayer"} + - {name: hole_layer_far_camera, type: "costmap_2d::ObstacleLayer"} + - {name: inflation_layer, type: "costmap_2d::InflationLayer"} + + diff --git a/params/costmap/map/3d_global_params.yaml b/params/costmap/map/3d_global_params.yaml new file mode 100644 index 0000000000000000000000000000000000000000..09fc474b71a4643b2f55a495eaafb61aac8b4b61 --- /dev/null +++ b/params/costmap/map/3d_global_params.yaml @@ -0,0 +1,24 @@ +#global_costmap: ###namespace added when loading parameters in move_base.launch +global_frame: map +update_frequency: 1.0 +publish_frequency: 1.0 +rolling_window: false + +plugins: + - {name: static_layer, type: "costmap_2d::StaticLayer"} + - {name: obstacle_layer_lidar, type: "costmap_2d::ObstacleLayer"} + - {name: obstacle_layer_camera, type: "costmap_2d::ObstacleLayer"} + - {name: hole_layer_near_camera,type: "costmap_2d::ObstacleLayer"} + - {name: hole_layer_far_camera, type: "costmap_2d::ObstacleLayer"} + - {name: inflation_layer, type: "costmap_2d::InflationLayer"} + +static_layer: + enabled: true + map_topic: /map + first_map_only: false + subscribe_to_updates: false + unknown_cost_value: -1 + use_maximum: false + lethal_cost_threshold: 100 + track_unknown_space: true + trinary_costmap: true diff --git a/params/costmap/no_map/3d_global_params.yaml b/params/costmap/no_map/3d_global_params.yaml new file mode 100644 index 0000000000000000000000000000000000000000..27c383a2547dc4fa1fd7ef61824da7877ff76967 --- /dev/null +++ b/params/costmap/no_map/3d_global_params.yaml @@ -0,0 +1,18 @@ +#global_costmap: ###namespace added when loading parameters in move_base.launch +global_frame: /ana/odom +update_frequency: 1.0 +publish_frequency: 0.0 +rolling_window: true +transform_tolerance: 1.0 +width: 20.0 +height: 20.0 +resolution: 0.2 +origin_x: 0.0 +origin_y: 0.0 + +plugins: + - {name: obstacle_layer_lidar, type: "costmap_2d::ObstacleLayer"} + - {name: obstacle_layer_camera, type: "costmap_2d::ObstacleLayer"} + - {name: hole_layer_near_camera, type: "costmap_2d::ObstacleLayer"} + - {name: hole_layer_far_camera, type: "costmap_2d::ObstacleLayer"} + - {name: inflation_layer, type: "costmap_2d::InflationLayer"}