File tree Expand file tree Collapse file tree 2 files changed +7
-3
lines changed
include/pointcloud_to_laserscan Expand file tree Collapse file tree 2 files changed +7
-3
lines changed Original file line number Diff line number Diff line change @@ -76,6 +76,7 @@ class FramePublisher
76
76
std::string frame_name_;
77
77
bool use_to_frame_translation_;
78
78
bool rot_z_, rot_x_, rot_y_;
79
+ geometry_msgs::TransformStamped published_msg_;
79
80
};
80
81
81
82
#endif // FRAME_PUB_H
Original file line number Diff line number Diff line change @@ -132,7 +132,10 @@ void FramePublisher::frameBroadcastCallback(const ros::TimerEvent& event)
132
132
// Broadcast new frame
133
133
geometry_msgs::TransformStamped published_msg = tf2::toMsg (published_tf);
134
134
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;
138
141
}
You can’t perform that action at this time.
0 commit comments