ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

Yes you can use a depth câmera plugin (for Gazebo simulator) to test it. I have already done this for my simulation actually.

You just need to get data from the camera/depth/raw topic or similar and feed the nav2_params.yaml file and include this camera topic in local costmap, observation sources. I guess the pre defined source is /scan

I've used a Kinect with nav2 as you can check here:https://youtu.be/v9CukFH6hj8

!-

- KINECT-->
  <gazebo reference="kinect_link">
      <sensor type="depth" name="kinect_sensor">
        <visualize>true</visualize>
        <!-- <always_on>0</always_on> -->
        <!-- Set update_rate only sensor, not on plugin -->
        <update_rate>30</update_rate>
          <camera name="kinect_camera">
              <horizontal_fov>1.047198</horizontal_fov>
              <image>
                  <width>640</width>
                  <height>480</height>
                  <format>R8G8B8</format>
              </image>
              <clip>
                <near>0.01</near>
                <far>20</far>
              </clip>
          </camera>
          <plugin name="kinect_plugin" filename="libgazebo_ros_camera.so">
            <baseline>0.2</baseline>
            <alwaysOn>true</alwaysOn>
            <updateRate>0.0</updateRate>
            <frame_name>kinect_depth_frame</frame_name>
            <pointCloudCutoff>0.5</pointCloudCutoff>
            <pointCloudCutoffMax>3.0</pointCloudCutoffMax>
            <distortionK1>0</distortionK1>
            <distortionK2>0</distortionK2>
            <distortionK3>0</distortionK3>
            <distortionT1>0</distortionT1>
            <distortionT2>0</distortionT2>
            <CxPrime>0</CxPrime>
            <Cx>0</Cx>
            <Cy>0</Cy>
            <focalLength>0</focalLength>
            <hackBaseline>0</hackBaseline>
          </plugin>
      </sensor>
  </gazebo>

The configuration file nav2_params.yaml

local_costmap:
    ros__parameters:
      update_frequency: 5.0
      publish_frequency: 2.0
      global_frame: odom
      robot_base_frame: base_link
      use_sim_time: True
      rolling_window: true
      width: 50
      height: 50
      resolution: 0.05
      #robot_radius: 0.22
      footprint:  "[[-4.8025, -1.274], [4.8025, -1.274], [4.8025, 1.274], [-4.8025, 1.274]]"
      plugins: ["voxel_layer", "inflation_layer"]
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 3.0
        inflation_radius: 2.0 #0.55
      voxel_layer:
        plugin: "nav2_costmap_2d::VoxelLayer"
        enabled: True
        publish_voxel_map: True
        origin_z: 2.0
        z_resolution: 0.5
        z_voxels: 16
        max_obstacle_height: 2.0 #2.0 # 3.5 m is > 3.041 meters (max truck height)
        min_obstacle_height: 0.0 # IGNORING GROUND AS OBSTACLE AND SMALL THING UNDER 0.5 Meters.
        mark_threshold: 0
        observation_sources: real_kinect_sensor/scan 
        real_kinect_sensor/scan:
          topic: /real_kinect_sensor/scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
          raytrace_max_range: 15.0 # Half of maximum lidar data range
          raytrace_min_range: 0.0
          obstacle_max_range: 15.0 # Half of maximum lidar data range
          obstacle_min_range: 0.0