Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Dual Return #208

Closed

Conversation

andre-nguyen
Copy link

@JWhitleyAStuff Hi There,
happy new year. This PR isn't complete but I'm posting this up to start a discussion. With this PR dual return works for my vlp16 dataset. The flashing in rviz is gone and all the points are tagged with their return type. There is also a check to see between two blocks to see if there was only one return and to prevent adding the same points in the cloud.

Since the return is encoded in the point cloud, you can visualize the returns in rviz as follows.

image

Here are the key implementation details:

  • There is still a single points topic but the return type is added to the points.
  • The point type is changed to add the return type.
  • There is a new dual return mode parameter.
  • For the vlp16 the factory bytes are now parsed to check what the return mode is. Since there is only 1 topic, this does not affect when the topic will appear as we had discussed.
  • There is a check in rawdata.cc to prevent adding a point twice in the cloud if it ends up being a single return.

I'd be interested in generalizing this to other lidars however I don't have any datasets and I only have access to a vlp16.

@andre-nguyen
Copy link
Author

@JWhitleyAStuff ping

Copy link
Contributor

@JWhitleyWork JWhitleyWork left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please review my suggestions in the code. I definitely agree with your overall approach and I think the changes make sense. However, there is at least one bug preventing CI from passing and, as you mentioned, it needs testing on other sensors.

velodyne_driver/src/driver/driver.cc Outdated Show resolved Hide resolved
velodyne_pointcloud/launch/VLP16_points.launch Outdated Show resolved Hide resolved
velodyne_pointcloud/src/lib/rawdata.cc Outdated Show resolved Hide resolved
@@ -327,7 +329,9 @@ inline float SQR(float val) { return val*val; }
float x, y, z;
float intensity;

const raw_packet_t *raw = (const raw_packet_t *) &pkt.data[0];
const raw_packet_vlp16_t *raw = (const raw_packet_vlp16_t *) &pkt.data[0];
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Go ahead and change the VLP-16-specific stuff to be sensor-generic and I'll test the changes on a VLP-32C and an HDL-64E.

Copy link
Author

@andre-nguyen andre-nguyen Jan 20, 2019

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Would it be possible for you to send me a PCAP of each? I made the raw_packet_vlp16_t to access the factory bytes (the packet definition is different from the rest of the lidars) I could technically just follow the datasheets to modify the other unpack function but it will likely be wrong without a pcap for me to test.

Also I will squash all the commits once it is ready to merge.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks, Andre. I'm working on getting you PCAPs for the two sensors I mentioned.

@JWhitleyWork
Copy link
Contributor

@andre-nguyen - Sorry I haven't been able to get those pcap files yet. It's still on the list for my support team but they're pretty bogged down at the moment.

On another note, I've changed CI vendors for this repo and applied roslint across the whole thing. Would you mind merging master back into your fork?

@andre-nguyen andre-nguyen force-pushed the feature/dual_return branch 3 times, most recently from 1efe00d to 285a013 Compare March 29, 2019 15:58
@andre-nguyen
Copy link
Author

@JWhitleyAStuff Rebased and squashed on master. Still wouldn't merge until we have tested with multiple datasets.

Also, I sort of figured out through trial and error that my build wasn't going through due to roslint failures but I couldn't see that in the build logs. May I suggest changing the build scripts to put roslint as a separate stage in the pipeline and explicitely building roslint_{package_name}?

Side note: May I also suggest we change the CircleCI build script line
catkin build to catkin build --no-status or catkin build --limit-status-rate 1 it makes the output logs easier to read.

@JWhitleyWork
Copy link
Contributor

Suggestions implemented in #231. Please merge again and verify that it looks good.

@andre-nguyen
Copy link
Author

Done deal, looks much neater! Let me know when those extra datasets come in.

@andre-nguyen
Copy link
Author

@JWhitleyAStuff
Ping for those datasets.

@JWhitleyWork
Copy link
Contributor

@andre-nguyen I'm very sorry I haven't been able to provide the datasets. This PR is still valid and I'd like to get to it in the future but my priorities keep shifting. Can you please rebase it on master to fix the conflicts?

@andre-nguyen
Copy link
Author

andre-nguyen commented Oct 15, 2019

🤷‍♂️ Glad you're still interested in this PR! The next few weeks are a bit loaded on my end, can you ping me again when you have data and I'll rebase and test everything in one go?

@mark-rosenblum
Copy link

mark-rosenblum commented Nov 7, 2019

Hi.
My name is Mark. We tried using the dual return mode on our VLP-16 Hi Res. I was seeing a few issues. At first I thought is was the velodyne itself, but I ran veloview and did not see the same issues. The two issues I encountered were:
Issue 1: From frame-to-frame, the dual-return characteristics change dramatically.
This can be seen in images good_dual_return_response.jpg and bad_dual_return_response.jpg. These images were grabbed between two successive frames of lidar data. The good response is persistent for multiple frames and then it lapses into a bad response.

Issue 2: There is a dramatic change in dual return characteristics across the 0 degree angle of the sensor within the same frame of data (cable coming out of the back is considered +180 degrees).
This can be seen in image center_angle_issue.jpg. In this case, a pickup truck is directly in front of the sensor with approximately half to the right and half to the left of the 0 degree angle. Again, I drew the lines between strongest and last response. You will see that on the right side of the image (+ angle), the lines are much longer than the left side of the image (-angle).

Description of the images
The images were produced by grabbing screenshots of rviz. In the lower left corner of the images you will see a corresponding camera view of the scene. The 3D representation shows lines with the endpoint of each line being the last and the strongest response for each lidar reading. Where these measurements are radically different, you will see a long line and when the difference is small, you will see a point.

bad_dual_return_response
center_angle_issue
good_dual_return_response

Not sure you are still working this, but any advice or help would be greatly appreciated.

Thanks.
Mark

@andre-nguyen
Copy link
Author

Off the top of my head I cant see why data from one side of the lidar would be treated differently from the other such that you would get that response. Unfortunately I'm in the process of moving right now and I won't be able to look at this for another two weeks. 2 things would help:

  1. Can you show/explain what you saw in veloview that allows you to say what you are seeing is not the correct behavior?
  2. Posting your pcap or bag would be very useful.

@JWhitleyWork
Copy link
Contributor

@andre-nguyen I'm sorry that I was unable to get the data you requested. The priorities at AS just never made it possible. Unfortunately, I have now moved on to another job, making it impossible for me to gather the requested data. Given that and the large amount of changes that have been made to master since this was created, are you still interested in continuing development on this PR?

@andre-nguyen
Copy link
Author

I am, though I might just close the whole MR outright and open a new one. Funnily enough, I too have moved to a new job and had access to an HDL-64 until covid hit. However, I do not have access to my origin VLP16-dual return data set because it belonged to my previous job.

I'll get in contact with you by email.

@chenpengxin
Copy link

chenpengxin commented Dec 22, 2021

A much easier way to get point clouds in the dual return mode is:

Just set return type=dual, rpm=1200 at the config page in web browser, but set rpm=600 in the /velodyne_pointcloud/launch/VLP16_points.launch .

It should be same for other types of sensors.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

4 participants