Skip to content

Commit

Permalink
Publish map with correct frame
Browse files Browse the repository at this point in the history
  • Loading branch information
benemer committed Dec 18, 2024
1 parent 0395784 commit 07020e8
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 10 deletions.
5 changes: 4 additions & 1 deletion ros/src/OdometryServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,7 +200,10 @@ void OdometryServer::PublishClouds(const std::vector<Eigen::Vector3d> frame,

frame_publisher_->publish(std::move(EigenToPointCloud2(frame, header)));
kpoints_publisher_->publish(std::move(EigenToPointCloud2(keypoints, header)));
map_publisher_->publish(std::move(EigenToPointCloud2(kiss_map, kiss_pose, header)));

auto local_map_header = header;
local_map_header.frame_id = lidar_odom_frame_;
map_publisher_->publish(std::move(EigenToPointCloud2(kiss_map, local_map_header)));
}
} // namespace kiss_icp_ros

Expand Down
9 changes: 0 additions & 9 deletions ros/src/Utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -228,13 +228,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

0 comments on commit 07020e8

Please sign in to comment.