Laser reflection intensity of the gazebo model

Hello everyone!I built a world model in gazebo, which contains a circular reflector. Then I want to detect this reflector by the reflection intensity value of the 2D laser. So what properties should I set for the laser sensor and the circular reflector?
The following are my current settings for the laser and circular reflector, but the intensity of the laser reflection is not correct. Does anyone know where I should improve?
for laser:

<gazebo reference="laser_Link">
    <material>Gazebo/Blue</material>
    <turnGravityOff>true</turnGravityOff>
    <sensor type="ray" name="sick_lms1xx">
      <pose>0 0 0 0 0 0</pose>
      <visualize>false</visualize>
      <update_rate>50</update_rate>
      <ray>
        <scan>
          <horizontal>
            <samples>720</samples>
            <resolution>1</resolution>
            <min_angle>-1.570796</min_angle>
            <max_angle>1.570796</max_angle>
          </horizontal>
        </scan>
        <range>
          <min>0.1</min>
          <max>30.0</max>
          <resolution>0.01</resolution>
        </range>
        <noise>
          <type>gaussian</type>
          <mean>0.0</mean>
          <stddev>0.001</stddev>
        </noise>
      </ray>
      <plugin name="gazebo_ros_laser" filename="libgazebo_ros_laser.so">
        <topicName>/scan</topicName>
        <frameName>laser_Link</frameName>
      </plugin>
    </sensor>
  </gazebo>

for the model of circular reflector:

    <model name='unit_cylinder_1'>
      <static>1</static>
      <pose frame=''>3.6685 -4.88865 0 0 0 0</pose>
      <link name='link'>
        <inertial>
          <mass>1</mass>
          <inertia>
            <ixx>0</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0</iyy>
            <iyz>0</iyz>
            <izz>0</izz>
          </inertia>
        </inertial>
        <collision name='collision'>
          <geometry>
            <cylinder>
              <radius>0.5</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <max_contacts>10</max_contacts>
          <surface>
            <contact>
              <ode/>
            </contact>
            <bounce/>
            <friction>
              <torsional>
                <ode/>
              </torsional>
              <ode/>
            </friction>
          </surface>
        </collision>
        <visual name='visual'>
          <geometry>
            <cylinder>
              <radius>0.1</radius>
              <length>3</length>
            </cylinder>
          </geometry>
          <material>
            <script>
              <name>Gazebo/Grey</name>
              <uri>file://media/materials/scripts/gazebo.material</uri>
            </script>
            <ambient>1 1 1 1</ambient>
            <diffuse>1 1 1 1</diffuse>
            <specular>1 1 1 1</specular>
            <emissive>1 1 1 1</emissive>
          </material>
         <laser_retro>1000.0</laser_retro>
        </visual>
        <self_collide>0</self_collide>
        <kinematic>0</kinematic>
        <gravity>1</gravity>
      </link>
    </model>

you also have to put <laser_retro>1000.0</laser_retro> in collision
like this

<collision name='collision'>
        <laser_retro>1000.0</laser_retro>