From 5d4bad78e3245b260de6eccec620a7e5f4402848 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Tue, 9 Jan 2024 15:24:47 +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 80f986730..09544c975 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp @@ -123,7 +123,7 @@ void Vls128Decoder::reset_overflow(double time_stamp) // be relative to the overflow's packet timestamp double new_timestamp_seconds = scan_timestamp_ + 1e-9 * overflow_point.time_stamp - last_block_timestamp_; - overflow_point.time_stamp = new_timestamp_seconds < 0.0 ? 0.0 : 1e9 * new_timestamp_seconds; + overflow_point.time_stamp = static_cast(new_timestamp_seconds < 0.0 ? 0.0 : 1e9 * new_timestamp_seconds); scan_pc_->points.emplace_back(overflow_point); overflow_pc_->points.pop_back();