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

Remove unused EigenToPointCloud2 #416

Merged
merged 1 commit into from
Jan 7, 2025
Merged
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
14 changes: 0 additions & 14 deletions ros/src/Utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,11 +185,6 @@ inline void FillPointCloud2XYZ(const std::vector<Eigen::Vector3d> &points, Point
}
}

inline void FillPointCloud2Timestamp(const std::vector<double> &timestamps, PointCloud2 &msg) {
sensor_msgs::PointCloud2Iterator<double> msg_t(msg, "time");
for (size_t i = 0; i < timestamps.size(); i++, ++msg_t) *msg_t = timestamps[i];
}

inline std::vector<double> GetTimestamps(const PointCloud2::ConstSharedPtr msg) {
auto timestamp_field = GetTimestampField(msg);
if (!timestamp_field.has_value()) return {};
Expand Down Expand Up @@ -228,13 +223,4 @@ inline std::unique_ptr<PointCloud2> EigenToPointCloud2(const std::vector<Eigen::
[&](const auto &point) { return T * point; });
return EigenToPointCloud2(points_t, header);
}

inline std::unique_ptr<PointCloud2> EigenToPointCloud2(const std::vector<Eigen::Vector3d> &points,
const std::vector<double> &timestamps,
const Header &header) {
auto msg = CreatePointCloud2Msg(points.size(), header, true);
FillPointCloud2XYZ(points, *msg);
FillPointCloud2Timestamp(timestamps, *msg);
return msg;
}
} // namespace kiss_icp_ros::utils
Loading