|
| 1 | +global_costmap: |
| 2 | + global_costmap: |
| 3 | + ros__parameters: |
| 4 | + rgbd_obstacle_layer: |
| 5 | + plugin: "spatio_temporal_voxel_layer/SpatioTemporalVoxelLayer" |
| 6 | + enabled: true |
| 7 | + voxel_decay: 1.0 # seconds if linear, e^n if exponential |
| 8 | + decay_model: 0 # 0=linear, 1=exponential, -1=persistent |
| 9 | + voxel_size: 0.05 # meters |
| 10 | + track_unknown_space: true # default space is known |
| 11 | + mark_threshold: 0 # voxel height |
| 12 | + update_footprint_enabled: true |
| 13 | + combination_method: 1 # 1=max, 0=override |
| 14 | + origin_z: 0.0 # meters |
| 15 | + publish_voxel_map: false # default off |
| 16 | + transform_tolerance: 0.2 # seconds |
| 17 | + mapping_mode: false # default off, saves map not for navigation |
| 18 | + map_save_duration: 60.0 # default 60s, how often to autosave |
| 19 | + observation_sources: rgbd1_mark rgbd1_clear |
| 20 | + rgbd1_mark: |
| 21 | + data_type: PointCloud2 |
| 22 | + topic: camera1/depth/points |
| 23 | + marking: true |
| 24 | + clearing: false |
| 25 | + obstacle_range: 3.0 # meters |
| 26 | + min_obstacle_height: 0.3 # default 0, meters |
| 27 | + max_obstacle_height: 2.0 # default 3, meters |
| 28 | + expected_update_rate: 0.0 # default 0, if not updating at this rate at least, remove from buffer |
| 29 | + observation_persistence: 0.0 # default 0, use all measurements taken during now-value, 0=latest |
| 30 | + inf_is_valid: false # default false, for laser scans |
| 31 | + filter: "passthrough_relative" # default passthrough, apply "voxel", "passthrough", their relative variants or no filter to sensor data, recommend on |
| 32 | + z_reference_frame: "base_link" # if unspecified keeps using global frame for z filter, frame to calcualte the z coordinate before transforming pointcloud to global frame |
| 33 | + voxel_min_points: 0 # default 0, minimum points per voxel for voxel filter |
| 34 | + clear_after_reading: true # default false, clear the buffer after the layer gets readings from it |
| 35 | + rgbd1_clear: |
| 36 | + data_type: PointCloud2 |
| 37 | + topic: camera1/depth/points |
| 38 | + marking: false |
| 39 | + clearing: true |
| 40 | + max_z: 7.0 # default 0, meters |
| 41 | + min_z: 0.1 # default 10, meters |
| 42 | + vertical_fov_angle: 0.8745 # default 0.7, radians |
| 43 | + horizontal_fov_angle: 1.048 # default 1.04, radians |
| 44 | + decay_acceleration: 1.0 # default 0, 1/s^2. If laser scanner MUST be 0 |
| 45 | + model_type: 0 # default 0, model type for frustum. 0=depth camera, 1=3d lidar like VLP16 or similar |
0 commit comments