Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix timestamping, see issues/1\#issuecomment-1864760707 #8

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 7 additions & 1 deletion src/manager/source_driver_ros2.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@

#pragma once
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/clock.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <sstream>
#include <hesai_ros_driver/msg/udp_frame.hpp>
Expand Down Expand Up @@ -214,10 +215,15 @@ inline sensor_msgs::msg::PointCloud2 SourceDriver::ToRosMsg(const LidarDecodedFr
sensor_msgs::PointCloud2Iterator<float> iter_intensity_(ros_msg, "intensity");
sensor_msgs::PointCloud2Iterator<uint16_t> iter_ring_(ros_msg, "ring");
sensor_msgs::PointCloud2Iterator<double> iter_timestamp_(ros_msg, "timestamp");

rclcpp::Clock clock(RCL_ROS_TIME);
rclcpp::Time current_time = clock.now();
ros_msg.header.stamp = current_time;
int64_t nanoseconds = current_time.nanoseconds();
double timestamp_seconds = static_cast<double>(nanoseconds) * 1e-9;
for (size_t i = 0; i < frame.points_num; i++)
{
LidarPointXYZIRT point = frame.points[i];
frame.points[i].timestamp=timestamp_seconds;
*iter_x_ = point.x;
*iter_y_ = point.y;
*iter_z_ = point.z;
Expand Down