gpu_ray sensor number in a gazebo world is limited

Issue #2346 new
daniel m created an issue

It seems that there's a limitation to the number of the allowed gpu_ray sensors in gazebo world:

I have created a Velodyne sensor plugin that reads data from 36 tilted, spinning, ray sensors, and produces ROS a point cloud message.

If i use regular ray sensors, things are working fine, But if i switch to gpu_ray, and use more than 16 gpu_ray sensors some of them, do not produce any data, and if i use more than 24 gazebo is crashes

I am using :
Gazebo 8 (also happens with Gazebo 5 and 7)
Ubuntu 16.04
CPU : i7-7700K CPU @ 4.20GHz × 8 (also happens with Xeon(R) E5-1620 v3 @ 3.50GHz × 8 )
RAM : 16G
GPU : Nvidea Gefoce GTX1080 (also happens with Quadro K2200 and Quadro M5000 )

(i have also raised this issue in gazebo answers )

Comments (10)

  1. HooberB

    I have a similar issue recently. My Velodyne SDF model uses the libgazebo_ros_velodyne_laser.so plugin and 32 vertical beams. I've used this model successfully for a year. Within the last week, gazebo crashes when I try to subscribe to the pointcloud2 topic. If I change vertical scans to 1, 2, or 3, I can successfully listen to the topic (using 243 horizontal beams). My workaround is to switch my plugin to libgazebo_ros_block_laser.so and convert to pointcloud2.

    Gazebo Error: Exception [MultiRayShape.cc:127] index[7776] out of range[0-7776]
    terminate called after throwing an instance of 'gazebo::common::Exception'

  2. michele hallak

    We created the problem with gazebo source (gazebo 8). It seems that when running the server, it holds. As soon as we connect the client, the server crashes at the 5th GPULaser with the following core:

    #0  0x00007fffb7b8bd97 in ?? () from /usr/lib/x86_64-linux-gnu/OGRE-1.9.0/RenderSystem_GL.so
    #1  0x00007fffb7b458aa in Ogre::GLRenderSystem::_setTextureBlendMode(unsigned long, Ogre::LayerBlendModeEx const&) () from /usr/lib/x86_64-linux-gnu/OGRE-1.9.0/RenderSystem_GL.so
    #2  0x00007ffff75cefc5 in Ogre::RenderSystem::_setTextureUnitSettings(unsigned long, Ogre::TextureUnitState&) () from /usr/lib/x86_64-linux-gnu/libOgreMain.so.1.9.0
    #3  0x00007ffff7533934 in Ogre::SceneManager::_setPass(Ogre::Pass const*, bool, bool) () from /usr/lib/x86_64-linux-gnu/libOgreMain.so.1.9.0
    #4  0x00007fffed390994 in gazebo::rendering::GpuLaser::UpdateRenderTarget (this=0x5197900, _target=0x7fffbd188c48, _material=0x7fffbd199a38, _cam=0x7fffb45e77c8, _updateTex=true) at /home/robil/gazebo_parallel/src/gazebo/gazebo/rendering/GpuLaser.cc:316
    #5  0x00007fffed391a1c in gazebo::rendering::GpuLaser::RenderImpl (this=0x5197900) at /home/robil/gazebo_parallel/src/gazebo/gazebo/rendering/GpuLaser.cc:465
    #6  0x00007fffed328d03 in gazebo::rendering::Camera::Render (this=0x5197900, _force=false) at /home/robil/gazebo_parallel/src/gazebo/gazebo/rendering/Camera.cc:426
    #7  0x00007ffff59ef5ff in gazebo::sensors::GpuRaySensor::Render (this=0x1d25ce0) at /home/robil/gazebo_parallel/src/gazebo/gazebo/sensors/GpuRaySensor.cc:573
    #8  0x00007ffff59f6213 in std::_Mem_fn_base<void (gazebo::sensors::GpuRaySensor::*)(), true>::operator()<, void>(gazebo::sensors::GpuRaySensor*) const (this=0x196a6a0, __object=0x1d25ce0) at /usr/include/c++/5/functional:600
    #9  0x00007ffff59f5dcb in std::_Bind<std::_Mem_fn<void (gazebo::sensors::GpuRaySensor::*)()> (gazebo::sensors::GpuRaySensor*)>::__call<void, , 0ul>(std::tuple<>&&, std::_Index_tuple<0ul>) (this=0x196a6a0, __args=<unknown type in /home/robil/gazebo_parallel/devel_isolated/gazebo/lib/libgazebo_sensors.so.8, CU 0x24a1fe, DIE 0x2a833e>) at /usr/include/c++/5/functional:1074
    #10 0x00007ffff59f58ab in std::_Bind<std::_Mem_fn<void (gazebo::sensors::GpuRaySensor::*)()> (gazebo::sensors::GpuRaySensor*)>::operator()<, void>() (this=0x196a6a0) at /usr/include/c++/5/functional:1133
    #11 0x00007ffff59f4b4c in std::_Function_handler<void (), std::_Bind<std::_Mem_fn<void (gazebo::sensors::GpuRaySensor::*)()> (gazebo::sensors::GpuRaySensor*)> >::_M_invoke(std::_Any_data const&) (__functor=...) at /usr/include/c++/5/functional:1871
    #12 0x00007ffff7b77f7a in std::function<void ()>::operator()() const (this=0x196a678) at /usr/include/c++/5/functional:2267
    #13 0x00007ffff5a2995f in gazebo::event::EventT<void ()>::Signal() (this=0x7ffff6fd7660 <gazebo::event::Events::render>) at /home/robil/gazebo_parallel/src/gazebo/gazebo/common/Event.hh:299
    #14 0x00007ffff5a27b22 in gazebo::event::EventT<void ()>::operator()() (this=0x7ffff6fd7660 <gazebo::event::Events::render>) at /home/robil/gazebo_parallel/src/gazebo/gazebo/common/Event.hh:143
    #15 0x00007ffff5a3529b in gazebo::sensors::SensorManager::ImageSensorContainer::Update (this=0xddf850, _force=false) at /home/robil/gazebo_parallel/src/gazebo/gazebo/sensors/SensorManager.cc:698
    #16 0x00007ffff5a326ee in gazebo::sensors::SensorManager::Update (this=0x7ffff5cf6ae0 <SingletonT<gazebo::sensors::SensorManager>::GetInstance()::t>, _force=false) at /home/robil/gazebo_parallel/src/gazebo/gazebo/sensors/SensorManager.cc:171
    #17 0x00007ffff5a1f782 in gazebo::sensors::run_once (_force=false) at /home/robil/gazebo_parallel/src/gazebo/gazebo/sensors/SensorsIface.cc:118
    #18 0x00007ffff7b665c6 in gazebo::Server::Run (this=0x6ba5c0) at /home/robil/gazebo_parallel/src/gazebo/gazebo/Server.cc:580
    #19 0x0000000000403aa1 in main (argc=2, argv=0x7fffffffd608) at /home/robil/gazebo_parallel/src/gazebo/gazebo/server_main.cc:43
    

    So, it seems that the crash might be in OGRE.

    Can we get some advise how to proceed?

    Thanks

  3. daniel m reporter

    here is the SDF file :
    to prevent GAZEBO from crashing you can comment sensors 24 to 31, but than if you count the sensors that are shown (and also generate data) you will find only 16

    <?xml version="1.0" encoding="utf-8"?>
    <sdf version="1.5">
      <model name="velodyne16">
        <pose>0 0 0.5 0 0 0</pose>
    
    
     <!-- <plugin name="velodyne16_control" filename="libvelodyne16.so">  -->
           <!-- rotRate>10</rotRate>      <!-- HZ -->
           <!-- angleRes>0.200</angleRes> <!-- horiz resolution, deg -->
           <!-- verticalAngelMin>-10</verticalAngelMin> <!-- deg -->
     <!-- </plugin>  -->
    
    
        <link name="base">
          <pose>0 0 0.029335 0 0 0</pose>
          <inertial>
            <mass>1.2</mass>
            <inertia>
              <ixx>0.001087473</ixx>
              <iyy>0.001087473</iyy>
              <izz>0.001092437</izz>
              <ixy>0</ixy>
              <ixz>0</ixz>
              <iyz>0</iyz>
            </inertia>
          </inertial>
    
          <collision name="base_collision">
            <geometry>
              <cylinder>
                <radius>.04267</radius>
                <length>.05867</length>
              </cylinder>
            </geometry>
          </collision>
    
          <visual name="base_visual">
            <pose>0 0 -0.029335 0 0 0</pose>
            <geometry>
              <mesh>
                <uri>model://velodyne16/meshes/velodyne_base.dae</uri>
              </mesh>
            </geometry>
          </visual>
        </link>
    
    
        <link name="top">
          <pose>0 0 0.095455 0 0 0</pose>
          <inertial>
            <mass>0.1</mass>
            <inertia>
              <ixx>0.000090623</ixx>
              <iyy>0.000090623</iyy>
              <izz>0.000091036</izz>
              <ixy>0</ixy>
              <ixz>0</ixz>
              <iyz>0</iyz>
            </inertia>
          </inertial>
          <collision name="top_collision">
            <geometry>
              <cylinder>
                <radius>0.04267</radius>
                <length>0.07357</length>
              </cylinder>
            </geometry>
          </collision>
          <visual name="top_visual">
            <pose>0 0 -0.0376785 0 0 1.5707</pose>
            <geometry>
              <mesh>
                <uri>model://velodyne16/meshes/velodyne_top.dae</uri>
              </mesh>
            </geometry>
          </visual>
    
          <sensor type="gpu_ray" name="ray_0">
            <pose>0 0 -0.004645 1.5707 0 0.00</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_1">
            <pose>0 0 -0.004645 1.5707 0 0.00349</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_2">
            <pose>0 0 -0.004645 1.5707 0 0.00698</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_3">
            <pose>0 0 -0.004645 1.5707 0 0.01047</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_4">
            <pose>0 0 -0.004645 1.5707 0 0.01396</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
          <sensor type="gpu_ray" name="ray_5">
            <pose>0 0 -0.004645 1.5707 0 0.01745</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_6">
            <pose>0 0 -0.004645 1.5707 0 0.02094</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_7">
            <pose>0 0 -0.004645 1.5707 0 0.02443</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
        <sensor type="gpu_ray" name="ray_8">
            <pose>0 0 -0.004645 1.5707 0 0.02793</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_9">
            <pose>0 0 -0.004645 1.5707 0 0.03142</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_10">
            <pose>0 0 -0.004645 1.5707 0 0.03491</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_11">
            <pose>0 0 -0.004645 1.5707 0 0.03840</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_12">
            <pose>0 0 -0.004645 1.5707 0 0.04189</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
          <sensor type="gpu_ray" name="ray_13">
            <pose>0 0 -0.004645 1.5707 0 0.04538</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_14">
            <pose>0 0 -0.004645 1.5707 0 0.04887</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_15">
            <pose>0 0 -0.004645 1.5707 0 0.05236</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_16">
            <pose>0 0 -0.004645 1.5707 0 0.05585</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_17">
            <pose>0 0 -0.004645 1.5707 0 0.05934</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_18">
            <pose>0 0 -0.004645 1.5707 0 0.06283</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_19">
            <pose>0 0 -0.004645 1.5707 0 0.06632</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_20">
            <pose>0 0 -0.004645 1.5707 0 0.06981</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_21">
            <pose>0 0 -0.004645 1.5707 0 0.07330</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
    
          <sensor type="gpu_ray" name="ray_22">
            <pose>0 0 -0.004645 1.5707 0 0.07679</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
    
          <sensor type="gpu_ray" name="ray_23">
            <pose>0 0 -0.004645 1.5707 0 0.08029</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
    
          <sensor type="gpu_ray" name="ray_24">
            <pose>0 0 -0.004645 1.5707 0 0.08378</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_25">
            <pose>0 0 -0.004645 1.5707 0 0.08727</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_26">
            <pose>0 0 -0.004645 1.5707 0 0.09076</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
    
          <sensor type="gpu_ray" name="ray_27">
            <pose>0 0 -0.004645 1.5707 0 0.09425</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
          <sensor type="gpu_ray" name="ray_28">
            <pose>0 0 -0.004645 1.5707 0 0.09774</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
    
          <sensor type="gpu_ray" name="ray_29">
            <pose>0 0 -0.004645 1.5707 0 0.10123</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
    
          <sensor type="gpu_ray" name="ray_30">
            <pose>0 0 -0.004645 1.5707 0 0.10472</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
    
          <sensor type="gpu_ray" name="ray_31">
            <pose>0 0 -0.004645 1.5707 0 0.10821</pose>
            <visualize>true</visualize>
            <update_rate>1000</update_rate>
            <ray>
    
              <scan>
                <horizontal>
                  <samples>16</samples>
                  <resolution>1</resolution>
                  <min_angle>-0.17453</min_angle>
                  <max_angle>0.17453</max_angle>
                </horizontal>
              </scan>
    
              <range>
                <min>0.1</min>
                <max>70</max>
                <resolution>0.01</resolution>
              </range>
            </ray>
          </sensor>
    
    
    
    
    
        </link>
    
    
        <joint type="revolute" name="velodyne16_joint">
          <pose>0 0 -0.036785 0 0 0</pose>
          <parent>base</parent>
          <child>top</child>
          <axis>
            <xyz>0 0 1</xyz>
          </axis>
        </joint>
      </model>
    
    
    </sdf>
    
  4. Log in to comment