diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index b8da8ff..fa40aff 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -207,8 +207,8 @@ local_costmap: z_voxels: 16 max_obstacle_height: 2.0 mark_threshold: 0 - observation_sources: scan - scan: + observation_sources: rplidar oakd + rplidar: topic: /scan max_obstacle_height: 2.0 clearing: True @@ -218,6 +218,17 @@ local_costmap: raytrace_min_range: 0.0 obstacle_max_range: 2.5 obstacle_min_range: 0.0 + oak-d: # no frame set, uses frame from message + topic: /stereo/points + max_obstacle_height: 1.5 + min_obstacle_height: 0.02 + obstacle_max_range: 3.0 + obstacle_min_range: 0.0 + raytrace_max_range: 3.2 + raytrace_min_range: 0.0 + clearing: True + marking: True + data_type: "PointCloud2" static_layer: plugin: "nav2_costmap_2d::StaticLayer" map_subscribe_transient_local: True