We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent 7777632 commit 4e18b80Copy full SHA for 4e18b80
perception/multi_object_tracker/src/multi_object_tracker_core.cpp
@@ -222,8 +222,9 @@ void MultiObjectTracker::onTrigger()
222
} else {
223
// Publish if the next publish time is close
224
const double minimum_publish_interval = publisher_period_ * 0.70; // 70% of the period
225
- if ((current_time - last_published_time_).seconds() > minimum_publish_interval) {
226
- checkAndPublish(current_time);
+ const rclcpp::Time publish_time = this->now();
+ if ((publish_time - last_published_time_).seconds() > minimum_publish_interval) {
227
+ checkAndPublish(publish_time);
228
}
229
230
0 commit comments