diff --git a/ros/src/OdometryServer.cpp b/ros/src/OdometryServer.cpp index d6779dca..687c3b58 100644 --- a/ros/src/OdometryServer.cpp +++ b/ros/src/OdometryServer.cpp @@ -194,15 +194,13 @@ void OdometryServer::PublishOdometry(const Sophus::SE3d &kiss_pose, void OdometryServer::PublishClouds(const std::vector frame, const std::vector keypoints, - const std_msgs::msg::Header &lidar_header) { - // The internal map representation is in the lidar_odom_frame_ - std_msgs::msg::Header map_header; - map_header.frame_id = lidar_odom_frame_; - map_header.stamp = lidar_header.stamp; - - frame_publisher_->publish(std::move(EigenToPointCloud2(frame, lidar_header))); - kpoints_publisher_->publish(std::move(EigenToPointCloud2(keypoints, lidar_header))); - map_publisher_->publish(std::move(EigenToPointCloud2(kiss_icp_->LocalMap(), map_header))); + const std_msgs::msg::Header &header) { + const auto kiss_map = kiss_icp_->LocalMap(); + const auto kiss_pose = kiss_icp_->pose().inverse(); + + 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))); } } // namespace kiss_icp_ros diff --git a/ros/src/Utils.hpp b/ros/src/Utils.hpp index 03b32710..09c9cd8e 100644 --- a/ros/src/Utils.hpp +++ b/ros/src/Utils.hpp @@ -219,6 +219,16 @@ inline std::unique_ptr EigenToPointCloud2(const std::vector EigenToPointCloud2(const std::vector &points, + const Sophus::SE3d &T, + const Header &header) { + std::vector points_t; + points_t.resize(points.size()); + std::transform(points.cbegin(), points.cend(), points_t.begin(), + [&](const auto &point) { return T * point; }); + return EigenToPointCloud2(points_t, header); +} + inline std::unique_ptr EigenToPointCloud2(const std::vector &points, const std::vector ×tamps, const Header &header) {