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

Gap in the point cloud on Velodyne sensor #52

Closed
mebasoglu opened this issue Aug 15, 2023 · 6 comments
Closed

Gap in the point cloud on Velodyne sensor #52

mebasoglu opened this issue Aug 15, 2023 · 6 comments

Comments

@mebasoglu
Copy link
Collaborator

mebasoglu commented Aug 15, 2023

Description

When I use Nebula with VLP-16 on main branch, I saw a gap on the point cloud. The gap is flickering. Here is a video of the point cloud:

nebula-gap.mp4

Expected behavior

We should have a full point cloud without any gaps.

Actual behavior

There is gap which is flickering on the point cloud.

Steps to reproduce

Run the launch file for Velodyne on the main branch:

ros2 launch nebula_ros velodyne_launch_all_hw.xml sensor_model:=VLP16 sensor_ip:=192.168.1.208 data_port:=2368

And on the RViz2 screen the point cloud:
wrong

Additional context

I can provide a pcap file that I recorded from the sensor if it is needed.

@mebasoglu
Copy link
Collaborator Author

mebasoglu commented Aug 15, 2023

I think this bug is related to the scan_phase parameter. In here I have added a feature called "dynamic scan phase" and I don't see a gap in the point cloud with it. It works like this:

  1. When a UDP packet is received, the current system clock time is rounded up to the next second and a "first publish time" value is created if the UDP packet is the first received one. And until that first publish time comes, packets are skipped.
    https://github.com/leo-drive/nebula/blob/d53e0ff5a915f90466daa025ed23e7ac6e6d5464/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp#L87

  2. After reaching first publish time, the azimuth angle of the most recent received packet is published to "/scan_phase" topic. This publishing happens only once.

  3. The decoder node subscribes to "/scan_phase" and sets the parameter. Instead of using scan_phase from parameter, this new value is used while decoding the packets.
    https://github.com/leo-drive/nebula/blob/memin/dev/dynamic-scan-phase/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp#L93

This feature allows multiple driver instances publish PointCloud2 messages as close as possible so that the concatenate node won't miss any of the PointCloud2 messages. Here is the rqt_graph screenshot of raw point clouds:

pc2_lmemin

With this dynamic scan phase change feature, the gap issue was also solved.

What are your opinions about this? @drwnz @amc-nu

Thank you.

Edit: Upon further investigation I realized that this didn't solve the issue. The gap still exists. :(

@mebasoglu
Copy link
Collaborator Author

On the get_pointcloud() method in vlp16_decoder I changed the angle type from radians to degrees like the previous awf_velodyne driver and it worked.

Instead of these:

auto current_azimuth = scan_pc_->points.back().azimuth;
auto phase_diff = static_cast<size_t>(angles::to_degrees(2*M_PI + current_azimuth - phase)) % 360;

I added:

auto current_azimuth_deg = angles::to_degrees(scan_pc_->points.back().azimuth);
auto phase_diff_deg =
      static_cast<size_t>(360 + current_azimuth_deg - sensor_configuration_->scan_phase) % 360;

And the new while loop:

while (phase_diff_deg <= 180 && !scan_pc_->points.empty()) {
      overflow_pc_->points.push_back(scan_pc_->points.back());
      scan_pc_->points.pop_back();
      
      // current_azimuth = scan_pc_->points.back().azimuth;
      // phase_diff = static_cast<size_t>(angles::to_degrees(2*M_PI + current_azimuth - phase)) % 360;

      current_azimuth_deg = angles::to_degrees(scan_pc_->points.back().azimuth);
      phase_diff_deg =
        static_cast<size_t>(360 + current_azimuth_deg - sensor_configuration_->scan_phase) % 360;
    }

And now the gap is gone. I have only tested for VLP-16.

@amc-nu
Copy link
Contributor

amc-nu commented Aug 21, 2023

Fixed in #40
and
#50

@amc-nu amc-nu closed this as completed Aug 21, 2023
@mebasoglu
Copy link
Collaborator Author

Hello, I still face this issue with most recent commits on main branch.

nebula

@drwnz drwnz reopened this Aug 24, 2023
@drwnz
Copy link
Collaborator

drwnz commented Aug 24, 2023

@mebasoglu thank you, do you have a rosbag with packets topic you can share?
I have tested on our devices and there doesn't seem to be an issue, so if you have some data we can look at, that would be helpful!

@mebasoglu
Copy link
Collaborator Author

Hello @drwnz , while working on the vehicle I realized that it was my mistake to set scan phase properly. After configuring it correctly, there is no problem. I apologize for taking your time. Thank you.

amc-nu added a commit that referenced this issue Sep 11, 2023
* Fix(GetLidarCalibration)

* Skip GetInventory if unable to connect

* fix monitor

* clean

* remove comments

Signed-off-by: amc-nu <[email protected]>

* at128. remove warnings

Signed-off-by: amc-nu <[email protected]>

* decoder. check calibration

Signed-off-by: amc-nu <[email protected]>

* Saving calibration data from sensor (except AT128)

* Saving correction data from sensor (AT128)

* fix(AT128 path)

* info for debugging

* nebula_hesai_ros. at128 fallback to offline

Signed-off-by: amc-nu <[email protected]>

* syncGetLidarCalibrationFromSensor -> GetLidarCalibrationFromSensor (AT128)

* hesai_decoder_ros. message on tcp fail

Signed-off-by: amc-nu <[email protected]>

* comment out da902901c4cd900bfbf906caf76ae143fe4a88a6

* Check "start of packet" in correction data

* hesai_decoder. save dat file

Signed-off-by: amc-nu <[email protected]>

* TcpDriver startup delay for setup_sensor

* delay & retry

* at1282ex. return mode checks

Signed-off-by: amc-nu <[email protected]>

* check lock

* check "isOpen"

---------

Signed-off-by: amc-nu <[email protected]>
Co-authored-by: Kyutoku <[email protected]>
drwnz pushed a commit that referenced this issue Oct 25, 2023
* Fix get lidar calibration (#52)

* Fix(GetLidarCalibration)

* Skip GetInventory if unable to connect

* fix monitor

* clean

* remove comments

Signed-off-by: amc-nu <[email protected]>

* at128. remove warnings

Signed-off-by: amc-nu <[email protected]>

* decoder. check calibration

Signed-off-by: amc-nu <[email protected]>

* Saving calibration data from sensor (except AT128)

* Saving correction data from sensor (AT128)

* fix(AT128 path)

* info for debugging

* nebula_hesai_ros. at128 fallback to offline

Signed-off-by: amc-nu <[email protected]>

* syncGetLidarCalibrationFromSensor -> GetLidarCalibrationFromSensor (AT128)

* hesai_decoder_ros. message on tcp fail

Signed-off-by: amc-nu <[email protected]>

* comment out da902901c4cd900bfbf906caf76ae143fe4a88a6

* Check "start of packet" in correction data

* hesai_decoder. save dat file

Signed-off-by: amc-nu <[email protected]>

* TcpDriver startup delay for setup_sensor

* delay & retry

* at1282ex. return mode checks

Signed-off-by: amc-nu <[email protected]>

* check lock

* check "isOpen"

---------

Signed-off-by: amc-nu <[email protected]>
Co-authored-by: Kyutoku <[email protected]>

* cspell. fix typos

Signed-off-by: amc-nu <[email protected]>

* cspell. fix typos

Signed-off-by: amc-nu <[email protected]>

---------

Signed-off-by: amc-nu <[email protected]>
Co-authored-by: Kyutoku <[email protected]>
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

No branches or pull requests

3 participants