Skip to content

Commit 3e6b3e0

Browse files
committed
only publish on updated transform to avoid TF_REPEATED_DATA
1 parent 6c3575c commit 3e6b3e0

File tree

2 files changed

+7
-3
lines changed

2 files changed

+7
-3
lines changed

include/pointcloud_to_laserscan/frame_publisher.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,7 @@ class FramePublisher
7676
std::string frame_name_;
7777
bool use_to_frame_translation_;
7878
bool rot_z_, rot_x_, rot_y_;
79+
geometry_msgs::TransformStamped published_msg_;
7980
};
8081

8182
#endif // FRAME_PUB_H

src/frame_publisher.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,10 @@ void FramePublisher::frameBroadcastCallback(const ros::TimerEvent& event)
132132
// Broadcast new frame
133133
geometry_msgs::TransformStamped published_msg = tf2::toMsg(published_tf);
134134
published_msg.child_frame_id = frame_name_;
135-
published_msg.header.stamp = ros::Time::now(); //update stamp to avoid TF_REPEATED_DATA (noetic)
136-
tf_broadcaster_.sendTransform(published_msg);
137-
ROS_DEBUG_STREAM("FramePublisher::frameBroadcastCallback: published_msg:\n" << published_msg);
135+
if (published_msg != published_msg_) //only publish on updated transform to avoid TF_REPEATED_DATA (noetic)
136+
{
137+
tf_broadcaster_.sendTransform(published_msg);
138+
ROS_DEBUG_STREAM("FramePublisher::frameBroadcastCallback: published_msg:\n" << published_msg);
139+
}
140+
published_msg_ = published_msg;
138141
}

0 commit comments

Comments
 (0)