-
Notifications
You must be signed in to change notification settings - Fork 46
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
Comments
I think this bug is related to the
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: 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. :( |
On the Instead of these: nebula/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp Lines 63 to 64 in f82a6f8
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. |
@mebasoglu thank you, do you have a rosbag with packets topic you can share? |
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. |
* 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]>
* 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]>
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:
And on the RViz2 screen the point cloud:
Additional context
I can provide a pcap file that I recorded from the sensor if it is needed.
The text was updated successfully, but these errors were encountered: