From b47a3f94e9d29ab3f529206583089002cb76f3a4 Mon Sep 17 00:00:00 2001
From: Guilherme Rodrigues <guilherme.rodrigues@ait.ac.at>
Date: Fri, 15 Dec 2023 09:19:02 +0000
Subject: [PATCH] Use constructor of rclcpp::Time instead of conversion.

Signed-off-by: Guilherme Rodrigues <guilherme.rodrigues@ait.ac.at>
---
 src/laser_geometry.cpp | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/src/laser_geometry.cpp b/src/laser_geometry.cpp
index 1693a25c..d68ecb94 100644
--- a/src/laser_geometry.cpp
+++ b/src/laser_geometry.cpp
@@ -421,8 +421,8 @@ void LaserProjection::transformLaserScanToPointCloud_(
   double range_cutoff,
   int channel_options)
 {
-  rclcpp::Time start_time = scan_in.header.stamp;
-  rclcpp::Time end_time = scan_in.header.stamp;
+  rclcpp::Time start_time(scan_in.header.stamp, RCL_ROS_TIME);
+  rclcpp::Time end_time(scan_in.header.stamp, RCL_ROS_TIME);
   // TODO(anonymous): reconcile all the different time constructs
   if (!scan_in.ranges.empty()) {
     end_time = start_time + rclcpp::Duration::from_seconds(