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

Revision history [back]

click to hide/show revision 1
initial version

answered 2013-08-29 05:42:23 -0500

joq gravatar image

I have not tried that combination. Several questions and comments:

  • Are you using a recent version of the driver? It has fixes for the 64E S2. Are you running Hydro or Groovy?

  • Some 64E S2 models seem to run at 300 RPM, not the 600 RPM default. You should verify the speed of your device. Velodyne provides a procedure for configuring the speed, consult the manual if you need or want to change it.

  • Using nodelets rather than nodes would probably reduce your CPU overhead noticeably.

  • You should use the correct angles calibration for your device, params/64e_utexas.yaml is for an older model than your S2. The gencalibration.py script will convert the db.xml provided by Velodyne with your device into the YAML format used by the velodyne_pointcloud package.

  • The cloud node publishes data in the "/velodyne" frame to the /velodyne_points topic, not /velodyne/velodyne_points. Use rostopic list or rosgraph to verify what is actually being published. Also, rostopic hz will tell how often messages are actually sent.

  • The driver does not publish a transform from "/velodyne" to "/odom". How could it know that? You do need to provide one yourself.

  • Since your device is moving, something needs to transform "/velodyne" points into the "/odom" frame. Normally that would be done via the transform node instead of the cloud node. It transforms each packet as it's received, to minimise "smearing" of data as the device revolves. Unfortunately, that presumes you have a separate odometry source, publishing that transform for the conversion.

I am not sure what to recommend for the circular odometry dependency: the driver needs odometry for transforming data into a fixed "/odom" frame, but that's what you are trying to generate. If the vehicle is moving slowly enough and the device is rotating quickly enough, you may be able to get away with assuming the point cloud generated for each rotation is "instantaneous".

I am open to suggestions for how to change the driver to better support your use case. Perhaps we could write a different transform node and nodelet that would better suit your requirements. It is not clear to me how that would work, however.

I would expect other rotating LIDARs to exhibit similar problems. I would appreciate suggestions from people with experience doing similar things with those devices. Heading changes tend to cause more trouble than forward motion.

I have not tried that combination. Several questions and comments:

  • Are you using a recent version of the driver? It has fixes for the 64E S2. Are you running Hydro or Groovy?

  • Some 64E S2 models seem to run You should verify the speed of your device. I've seen examples at 300 RPM, but not the 600 RPM default. You should verify the speed of your device. 200 RPM, I don't think that is an option. Velodyne provides a procedure for configuring the speed, consult the manual if you need or want to change it.

  • Using nodelets rather than nodes would probably reduce your CPU overhead noticeably.

  • You should use the correct angles calibration for your device, params/64e_utexas.yaml is for an older model than your S2. The gencalibration.py script will convert the db.xml provided by Velodyne with your device into the YAML format used by the velodyne_pointcloud package.

  • The cloud node publishes data in the "/velodyne" frame to the /velodyne_points topic, not /velodyne/velodyne_points. Use rostopic list or rosgraph to verify what is actually being published. Also, rostopic hz will tell how often messages are actually sent.

  • The driver does not publish a transform from "/velodyne" to "/odom". How could it know that? You do need to provide one yourself.

  • Since your device is moving, something needs to transform "/velodyne" points into the "/odom" frame. Normally that would be done via the transform node instead of the cloud node. It transforms each packet as it's received, to minimise "smearing" of data as the device revolves. Unfortunately, that presumes you have a separate odometry source, publishing that transform for the conversion.

I am not sure what to recommend for the circular odometry dependency: the driver needs odometry for transforming data into a fixed "/odom" frame, but that's what you are trying to generate. If the vehicle is moving slowly enough and the device is rotating quickly enough, you may be able to get away with assuming the point cloud generated for each rotation is "instantaneous".

I am open to suggestions for how to change the driver to better support your use case. Perhaps we could write a different transform node and nodelet that would better suit your requirements. It is not clear to me how that would work, however.

I would expect other rotating LIDARs to exhibit similar problems. I would appreciate suggestions from people with experience doing similar things with those devices. Heading changes tend to cause more trouble than forward motion.