Skip to content

Commit

Permalink
Restore ros utils to master
Browse files Browse the repository at this point in the history
  • Loading branch information
tizianoGuadagnino committed Nov 15, 2024
1 parent 8ed5562 commit 64760cc
Showing 1 changed file with 1 addition and 6 deletions.
7 changes: 1 addition & 6 deletions ros/src/kinematic_icp_ros/utils/RosUtils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,7 @@ namespace kinematic_icp_ros::utils {
std::optional<PointField> GetTimestampField(const PointCloud2::ConstSharedPtr msg) {
PointField timestamp_field;
for (const auto &field : msg->fields) {
if ((field.name == "t" || field.name == "timestamp" || field.name == "time" ||
field.name == "stamps")) {
if ((field.name == "t" || field.name == "timestamp" || field.name == "time")) {
timestamp_field = field;
}
}
Expand Down Expand Up @@ -62,7 +61,6 @@ auto ExtractTimestampsFromMsg(const PointCloud2::ConstSharedPtr msg,
const uint64_t number_of_seconds = static_cast<uint64_t>(std::round(stamp));
return number_of_seconds > 0 ? std::floor(std::log10(number_of_seconds) + 1) : 1;
};
const double msg_stamp_in_sec = rclcpp::Time(msg->header.stamp).nanoseconds() * 1e-9;
auto extract_timestamps =
[&]<typename T>(sensor_msgs::PointCloud2ConstIterator<T> &&it) -> std::vector<double> {
const size_t n_points = msg->height * msg->width;
Expand All @@ -76,9 +74,6 @@ auto ExtractTimestampsFromMsg(const PointCloud2::ConstSharedPtr msg,
if (number_of_digits_decimal_part(stampd) > 10) {
stampd *= 1e-9;
}
if (stampd < msg_stamp_in_sec) {
stampd += msg_stamp_in_sec;
}
timestamps.emplace_back(stampd);
}
return timestamps;
Expand Down

0 comments on commit 64760cc

Please sign in to comment.