From 9d7768cb40c134ae8a5f89dcbe376e55d21373c1 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Tue, 9 Jan 2024 17:02:01 +0900 Subject: [PATCH] Update nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp Co-authored-by: Benjamin Gilby <40575701+bgilby59@users.noreply.github.com> --- .../src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp index 09544c975..b621d5482 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp @@ -106,7 +106,7 @@ void Vls128Decoder::reset_overflow(double time_stamp) const double last_overflow_time_stamp = scan_timestamp_ + 1e-9 * overflow_pc_->points.back().time_stamp; - // Detect cases where there in an unacceptable time difference between the last overflow point and + // Detect cases where there is an unacceptable time difference between the last overflow point and // the first point of the next packet. In that case, there was probably a packet drop so it is // better to ignore the overflow pointcloud if (time_stamp - last_overflow_time_stamp > 0.05) {