When running in a simulated Velodyne VLP-16 in gazebo, you can check the real time factor. I used it almost an year ago and it ran at 0.3 * time real time, but it will vary depending upon your pc specs. At that point plugin ran on CPU, and around a month ago they released it with gpu support so it would definitely improve real time factor alot.
<gazebo reference="${name}_link">
<sensor type="${sensor_type}" name="VLP16">
<pose>0 0 0 0 0 0</pose>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>-${M_PI}</min_angle>
<max_angle> ${M_PI}</max_angle>
</horizontal>
<vertical>
<samples>16</samples>
<resolution>1</resolution>
<min_angle>-${15.0*M_PI/180.0}</min_angle>
<max_angle> ${15.0*M_PI/180.0}</max_angle>
</vertical>
</scan>
<range>
<min>1.0</min>
<max>140.0</max>
<resolution>0.001</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_velodyne_laser.so">
<topicName>${ros_topic}</topicName>
<frameName>${name}_link</frameName>
<min_range>1.0</min_range>
<max_range>140.0</max_range>
<gaussianNoise>0.008</gaussianNoise>
</plugin>
</sensor>
</gazebo>
It's pretty straight forward, beams (samples) along x, along y, M_PI is 3.14, and ranges is between 1-140 m, that's more or less what actual thing has. You can also add noise if you wish.
Hope this answered your question.