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

fix(velodyne): reset pointcloud correctly, including width and height fields #216

Merged
merged 1 commit into from
Nov 5, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ int Vlp16Decoder::points_per_packet()

void Vlp16Decoder::reset_pointcloud(double time_stamp)
{
scan_pc_->points.clear();
scan_pc_->clear();
reset_overflow(time_stamp); // transfer existing overflow points to the cleared pointcloud
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,8 +83,7 @@ int Vlp32Decoder::points_per_packet()

void Vlp32Decoder::reset_pointcloud(double time_stamp)
{
// scan_pc_.reset(new NebulaPointCloud);
scan_pc_->points.clear();
scan_pc_->clear();
reset_overflow(time_stamp); // transfer existing overflow points to the cleared pointcloud
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,8 +86,7 @@ int Vls128Decoder::points_per_packet()

void Vls128Decoder::reset_pointcloud(double time_stamp)
{
// scan_pc_.reset(new NebulaPointCloud);
scan_pc_->points.clear();
scan_pc_->clear();
reset_overflow(time_stamp); // transfer existing overflow points to the cleared pointcloud
}

Expand Down
Loading