Skip to content

Commit 4fbdd8d

Browse files
Benedikt MerschtizianoGuadagnino
andauthored
Publish map in odom_lidar frame (#417)
* Publish map with correct frame * Isolate changes --------- Co-authored-by: tizianoGuadagnino <frevo93@gmail.com>
1 parent 5900455 commit 4fbdd8d

File tree

1 file changed

+4
-1
lines changed

1 file changed

+4
-1
lines changed

ros/src/OdometryServer.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -199,7 +199,10 @@ void OdometryServer::PublishClouds(const std::vector<Eigen::Vector3d> frame,
199199

200200
frame_publisher_->publish(std::move(EigenToPointCloud2(frame, header)));
201201
kpoints_publisher_->publish(std::move(EigenToPointCloud2(keypoints, header)));
202-
map_publisher_->publish(std::move(EigenToPointCloud2(kiss_map, kiss_pose, header)));
202+
203+
auto local_map_header = header;
204+
local_map_header.frame_id = lidar_odom_frame_;
205+
map_publisher_->publish(std::move(EigenToPointCloud2(kiss_map, local_map_header)));
203206
}
204207
} // namespace kiss_icp_ros
205208

0 commit comments

Comments
 (0)