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

Packet rate of Velodyne HDL-64E in velodyne_driver [closed]

asked 2013-07-14 22:09:54 -0600

Gabor Meszaros gravatar image

updated 2014-01-28 17:17:15 -0600

ngrennan gravatar image

Hi Everyone,

I am trying to understand the velodyne_driver code where I found the following:

// get model name, validate string, determine packet rate
private_nh.param("model", config_.model, std::string("64E"));
double packet_rate;                   // packet frequency (Hz)
if (config_.model == "64E")
  {
    packet_rate = 2600.0;
  }
else if (config_.model == "32E")
  {
    packet_rate = 1808.0;
  }
else
  {
    ROS_ERROR_STREAM("unknown Velodyne LIDAR model: " << config_.model);
    packet_rate = 2600.0;
  }

I did not know why the packet rate is 2600 so I checked the Velodyne HDL-64E manual and it writes:

Data Packet Construction

The HDL-64E S2 outputs UDP Ethernet packets. Each packet contains a data payload of 1206 bytes that consists of 12 blocks of 100-byte firing data followed by six bytes at the end of each packet that contains a spin counter and firmware version information. Each packet can be for either the upper or lower laser banks (called “laser blocks”) - each bank contains 32 lasers.

The packet format is as follows:

  • 2 bytes of header info. This header indicates whether the packet is for the upper block or the lower block. The upper block will have a header of 0xEEFF and the lower block will have a header of 0xDDFF.
  • 2 bytes of rotational info. This is an integer between 0 and
    1. Divide this number by 100 to get degrees from 0.
  • 32 laser returns broken into 3 bytes each. Each return contains two bytes of distance information in .2 centimeter [2mm] increments, and one byte of intensity information (0 – 255, with 255 being the most intense return). A zero distance value within the data packet indicates there are no returns up to 120 meters, the maximum range of the device.

This:

The HDL-64E S2 can spin at rates ranging from 300 RPM (5 Hz) to 900 RPM (15 Hz). The default is 600 RPM (10 Hz). Note that changing the spin rate does not change the data rate - the unit will send out the same number of packets (at a rate of 1.3 million data points per second) regardless of spin rate. The image resolution will increase or decrease depending on rotation speed.

And also this:

20,833 points per second, per laser x 64 = 1,333,312 total points per second therefore, the HDL-64E S2 generates greater than 1.3 million points per second.

So, according the the manual:

  • Each packet contains a data payload of 1206 bytes that consists of 12 blocks of 100-byte firing data
  • Each firing data contains 32 laser returns
  • In 1 second the device generates 1 333 312 points.

It means 1 packet contains 384 laser returns therefore the packet rate should be about 3472.

Do I misunderstand something?

Update: Thanks joq! I read both the 64E and the 64E S2 manuals and you are right, they generate different number of point per second. The 64E one generates 1 000 000 points per second meanwhile the 64E S2 generates the mentioned 1 333 312 points per second.

In case of 64E's 1 000 000 points the calculated ... (more)

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by Gabor Meszaros
close date 2013-07-28 22:09:01

Comments

1

Thanks for the bug report, I created a github issue for it: https://github.com/ros-drivers/velodyne/issues/11

joq gravatar image joq  ( 2013-07-17 07:20:56 -0600 )edit

1 Answer

Sort by » oldest newest most voted
2

answered 2013-07-16 15:42:49 -0600

joq gravatar image

updated 2016-12-06 09:11:54 -0600

The 64E rate is an experimental result with our non-S2 device. I don't have access to an S2. Can you confirm the numbers above with it? If necessary we can add another model designation for the S2.

Update: a patch would be great. I think it'll be straightforward, so you can concentrate on the github mechanics. Just ask, if you need help.

The only other 64E S2 user I've heard from was a couple of years ago. He provided a patch for his angles configuration extensions. Since you have access to an S2, we should set up a unit test of some kind. Perhaps you can supply the angles configuration for your device. The velodyne_pointcloud/params/utexas_64e.yaml is for our older, non-S2 device.

Update2: for anyone using an earlier version of the driver without this fix, here is a work-around for the 64E S2 or S2.1:

$ rosrun velodyne_driver velodyne_node _npackets:=384 _rpm:=600

EDIT: corrected npackets typo (was 348)

edit flag offensive delete link more

Comments

Sure, I can give it to you. I have a question about the patch, but I will ask it on the issue's github page. Thank you!

Gabor Meszaros gravatar image Gabor Meszaros  ( 2013-07-17 23:46:05 -0600 )edit

Good. To keep this from breaking again in the future I'd like a short (~20MB) PCAP dump file from your device. That way I can create a unit test like the existing ones for 32E and our old 64E.

joq gravatar image joq  ( 2013-07-18 06:29:42 -0600 )edit

I find the same quesiton in Velodyne HDL32-E,the horizontal resolution is 0.16 degree,so the package rate is 1875, but I want to know where can I modify the paramter, I have install the driver,Shoud I change the code,then catkin_make by myself?

pengpeng gravatar image pengpeng  ( 2016-05-09 08:54:25 -0600 )edit

The current master uses 1808 for the 32e packet rate. If you believe that is wrong, please open an issue. We can discuss it there.

joq gravatar image joq  ( 2016-05-09 12:35:31 -0600 )edit

You can override the packet rate by explicitly setting the npackets parameter to whatever you like.

joq gravatar image joq  ( 2016-05-09 12:37:01 -0600 )edit

Thank you for your reply,I change the npackets to 1875,But I still can't get a circle,some sectors still had't data,moreover,I compared with the data from the veloview ,I found it had some difference,Can you tell me why

pengpeng gravatar image pengpeng  ( 2016-05-09 22:22:51 -0600 )edit

@joq I believe there is a small typo in your workaround

rosrun velodyne_driver velodyne_node _npackets:=348 _rpm:=600

should read

rosrun velodyne_driver velodyne_node _npackets:=384 _rpm:=600

teddyort gravatar image teddyort  ( 2016-12-06 01:20:45 -0600 )edit

Thanks! So, noted.

joq gravatar image joq  ( 2016-12-06 09:12:07 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2013-07-14 22:09:54 -0600

Seen: 3,859 times

Last updated: Dec 06 '16