Robotics StackExchange | Archived questions

Velodyne VLP-16 is showing only 1 beam instead of 16 beams in Gazebo

I am trying to build a Velodyne VLP-16 but using the official documentation of the velodyne hdl-32 as I would like to replicate the physical simulation in Gazebo. As you can see in the image below I am only getting 1 beam instead of 16 beams.

error

What I was expecting was something similar to the image below with all the 16 beams:

vlp16

Below the xml file I have been working on, but now I stopped because of that:

<?xml version="1.0" ?>
<sdf version="1.5">
    <world name="location_monitor">
    <!-- A global light source -->
    <include>
        <uri>model://sun</uri>
    </include>
    <!-- A ground plane -->
    <include>
        <uri>model://ground_plane</uri>
    </include>

        <model name="velodyne_vlp_16">

            <!-- This is the BASE of the Lidar -->
            <link name="base">
            <!-- Offset the base by half the lenght of the cylinder -->
            <pose>0 0 0.0084 0 0 0</pose>

            <inertial>
              <mass>0.10</mass>
              <inertia>
                <ixx>0.000064852</ixx>
                <iyy>0.000064852</iyy>
                <izz>0.000125</izz>
                <ixy>0</ixy>
                <ixz>0</ixz>
                <iyz>0</iyz>
              </inertia>
            </inertial>

            <collision name="base_collision">
                <geometry>
                    <cylinder>
                    <!-- Radius and length provided by Velodyne -->
                    <radius>0.05</radius>
                    <length>0.0168</length>
                    </cylinder>
                </geometry>
            </collision>

            <!-- The visual is mostly a copy of the collision -->
            <visual name="base_visual">
                <geometry>
                    <cylinder>
                    <radius>0.05</radius>
                    <length>0.0168</length>
                    </cylinder>
                </geometry>
            </visual>
            </link>

            <!-- This is the TOP of the Lidar -->
            <link name="top">
            <!-- Vertically offset the top cylinder by the length of the bottom
                cylinder and half the length of this cylinder. -->
                <pose>0 0 0.0637 0 0 0</pose>

                <inertial>
                  <mass>0.10</mass>
                  <inertia>
                    <ixx>0.000064852</ixx>
                    <iyy>0.000064852</iyy>
                    <izz>0.000125</izz>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyz>0</iyz>
                  </inertia>
                </inertial>

                <collision name="top_collision">
                    <geometry>
                        <cylinder>
                        <!-- Radius and length provided by Velodyne -->
                        <radius>0.05</radius>
                        <length>0.0168</length>
                        </cylinder>
                    </geometry>
                </collision>

            <!-- The visual is mostly a copy of the collision -->
            <visual name="top_visual">
              <geometry>
                <cylinder>
                  <radius>0.05</radius>
                  <length>0.0168</length>
                </cylinder>
              </geometry>
            </visual>
          </link>

          <!-- LASER SCAN -->
          <link name="laser_scan">

            <sensor type="ray" name="sensor">

            <!-- Position the ray sensor based on the specification. also rotate
            it by 90 degree around the X-axis so that the horizontal rays become vertical-->
            <pose>0 0 -0.004645 1.5707 0 0</pose>

            <!-- Enable visualization to see the rays in the GUI -->
            <visualize>true</visualize>

            <!-- Set the update rate of the sensor -->
            <update_rate>30</update_rate>

                <ray>
                    <!-- The scan element contains the horizontal and vertical beams.
                    We are leaving out the vertical beams for now -->
                    <scan>
                    <!-- The horizontal beams -->
                        <horizontal>
                            <!-- The velodyne puck has 16 beams(samples)-->
                            <samples>16</samples>

                            <!-- Resolution is multiplied by samples to determine number of
                            simulated beams vs interpolated beams -->
                            <resolution>1</resolution>

                            <!-- Min angle in radians -->
                            <min_angle></min_angle>

                            <!-- Max angle in radians -->
                            <max_angle></max_angle>
                        </horizontal>
                    </scan>
                    <!-- Range definee characteristics of an individual beam -->
                    <range>
                        <!-- Minimum distance of the beam -->
                        <min>0.05</min>
                        <!-- Maximum distance of the beam -->
                        <max>100</max>
                        <!-- Linear resolution of the beam -->
                        <resolution>0.02</resolution>
                    </range>
                </ray>
            </sensor>

          <!-- Diminuisco la z e lo scan si abbassa -->
          <pose>0 0 0.036 0 0 0</pose>
            <inertial>
              <mass>0.63</mass>
              <inertia>
                <ixx>0.000469959</ixx>
                <iyy>0.000469959</iyy>
                <izz>0.0007875</izz>
                <ixy>0</ixy>
                <ixz>0</ixz>
                <iyz>0</iyz>
              </inertia>
            </inertial>

            <collision name="laser_collision">
              <geometry>
                  <cylinder>
                  <!-- Radius and length provided by Velodyne -->
                  <radius>0.05</radius>
                  <length>0.0381</length>
                  </cylinder>
              </geometry>
            </collision>

            <!-- The visual is mostly a copy of the collision -->
            <visual name="laser_visual">
            <geometry>
                <cylinder>
                <radius>0.05</radius>
                <length>0.0381</length>
                </cylinder>
              </geometry>
            </visual>
          </link>

          <!-- Each joint must have a unique name -->
          <joint type="revolute" name="base_joint">

            <!-- Position the joint at the bottom of the top link -->
            <pose>0 0 0.0004 0 0 0</pose>

            <!-- Use the base link as the parent of the joint -->
            <parent>base</parent>

            <!-- Use the top link as the child of the joint -->
            <child>laser_scan</child>

            <!-- The axis defines the joint's degree of freedom -->
            <axis>
              <!-- Revolve around the z-axis -->
              <xyz>0 0 1</xyz>
              <!-- Limit refers to the range of motion of the joint -->
              <limit>

                <!-- Use a very large number to indicate a continuous revolution -->
                <lower>-10000000000000000</lower>
                <upper>10000000000000000</upper>
              </limit>
            </axis>
          </joint>

          <!-- Each joint must have a unique name -->
          <joint type="revolute" name="top_joint">

            <!-- Position the joint at the bottom of the top link -->
            <pose>0 0 -0.0004 0 0 0</pose>
          <!--            0 0 0.0084 0 0 0-->

            <!-- Use the base link as the parent of the joint -->
            <parent>top</parent>

            <!-- Use the top link as the child of the joint -->
            <child>laser_scan</child>

            <!-- The axis defines the joint's degree of freedom -->
            <axis>
              <!-- Revolve around the z-axis -->
              <xyz>0 0 1</xyz>
              <!-- Limit refers to the range of motion of the joint -->
              <limit>

                <!-- Use a very large number to indicate a continuous revolution -->
                <lower>-10000000000000000</lower>
                <upper>10000000000000000</upper>
              </limit>
            </axis>
          </joint>
        </model>
    </world>
</sdf>

Thanks for shedding light on this problem.

Asked by RayGz on 2019-12-30 11:45:06 UTC

Comments

Answers