diff --git a/src/orb_slam3_ros/include/publish_ros_viz_topics.h b/src/orb_slam3_ros/include/publish_ros_viz_topics.h index 806a6a1..d77bd5a 100644 --- a/src/orb_slam3_ros/include/publish_ros_viz_topics.h +++ b/src/orb_slam3_ros/include/publish_ros_viz_topics.h @@ -7,6 +7,7 @@ #include "sophus/se3.hpp" #include "sophus/sim3.hpp" #include +#include #include #include #include @@ -51,6 +52,8 @@ class PublishRosVizTopics { shared_ptr node; ReferenceFrameManager* referenceFrameManager; + map last_sent_keyframe_poses; + // ROS publishers rclcpp::Publisher::SharedPtr pose_pub; rclcpp::Publisher::SharedPtr pose_marker_pub; diff --git a/src/orb_slam3_ros/src/publish_ros_viz_topics.cpp b/src/orb_slam3_ros/src/publish_ros_viz_topics.cpp index abba06e..b35585d 100644 --- a/src/orb_slam3_ros/src/publish_ros_viz_topics.cpp +++ b/src/orb_slam3_ros/src/publish_ros_viz_topics.cpp @@ -188,6 +188,15 @@ void PublishRosVizTopics::publish_keyframes(std::vector ke if (keyFrame->isBad()) continue; + // Skip if the keyframe has already been sent and hasn't moved + if (last_sent_keyframe_poses.find(keyFrame->uuid) != last_sent_keyframe_poses.end() + && last_sent_keyframe_poses[keyFrame->uuid].translation().isApprox(keyFrame->GetPoseInverse().translation()) + && last_sent_keyframe_poses[keyFrame->uuid].unit_quaternion().isApprox( + keyFrame->GetPoseInverse().unit_quaternion())) + continue; + + last_sent_keyframe_poses[keyFrame->uuid] = keyFrame->GetPoseInverse(); + visualization_msgs::msg::Marker keyFrameWireframe; keyFrameWireframe.header.frame_id = referenceFrameManager->slam_system_frame_id; keyFrameWireframe.ns = "keyFrameWireframes";