Skip to content

Commit

Permalink
fix(velodyne): reset pointcloud correctly, including width and height…
Browse files Browse the repository at this point in the history
… fields

Signed-off-by: Max SCHMELLER <[email protected]>
  • Loading branch information
mojomex committed Nov 5, 2024
1 parent a908f61 commit 501355f
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 5 deletions.
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

0 comments on commit 501355f

Please sign in to comment.