diff --git a/SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro b/SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro index 9290884dd..3f4517335 100644 --- a/SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro +++ b/SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro @@ -11,8 +11,6 @@ - - @@ -33,11 +31,6 @@ - - - - - diff --git a/mil_common/gnc/odometry_utils/src/odometry_to_tf.cpp b/mil_common/gnc/odometry_utils/src/odometry_to_tf.cpp index d2ec5a6bf..953f0fcbd 100644 --- a/mil_common/gnc/odometry_utils/src/odometry_to_tf.cpp +++ b/mil_common/gnc/odometry_utils/src/odometry_to_tf.cpp @@ -4,7 +4,9 @@ #include #include +#include #include +#include namespace odometry_utils { @@ -13,11 +15,17 @@ class odometry_to_tf : public nodelet::Nodelet private: ros::Subscriber odom_sub; tf::TransformBroadcaster tf_br; + std::map _last_tf_stamps; void handle_odom(const nav_msgs::Odometry::ConstPtr& msg) { tf::Transform transform; poseMsgToTF(msg->pose.pose, transform); + if (_last_tf_stamps.count(msg->header.frame_id) && _last_tf_stamps[msg->header.frame_id] <= msg->header.stamp) + { + return; + } + _last_tf_stamps[msg->header.frame_id] = msg->header.stamp; tf::StampedTransform stamped_transform(transform, msg->header.stamp, msg->header.frame_id, msg->child_frame_id); tf_br.sendTransform(stamped_transform); }