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 (#216)

Signed-off-by: Max SCHMELLER <max.schmeller@tier4.jp>
  • Loading branch information
mojomex authored Nov 5, 2024
1 parent a908f61 commit 24ace12
Showing 3 changed files with 3 additions and 5 deletions.
Original file line number Diff line number Diff line change
@@ -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
}

Original file line number Diff line number Diff line change
@@ -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
}

Original file line number Diff line number Diff line change
@@ -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
}

0 comments on commit 24ace12

Please sign in to comment.