Skip to content

Commit

Permalink
chore: declare min and max publish interval ratios
Browse files Browse the repository at this point in the history
Signed-off-by: Taekjin LEE <[email protected]>
  • Loading branch information
technolojin committed Aug 30, 2024
1 parent f371a6a commit ff8b646
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -159,6 +159,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
const auto timer_period = rclcpp::Rate(publish_rate * timer_multiplier).period();
publish_timer_ = rclcpp::create_timer(
this, get_clock(), timer_period, std::bind(&MultiObjectTracker::onTimer, this));

Check warning on line 162 in perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

MultiObjectTracker::MultiObjectTracker increases from 96 to 99 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
}

// Initialize processor
Expand Down Expand Up @@ -225,7 +226,7 @@ void MultiObjectTracker::onTimer()
const rclcpp::Time current_time = this->now();

// ensure minimum interval: room for the next process(prediction)
const double minimum_publish_interval = publisher_period_ * 0.85; // 85% of the period
const double minimum_publish_interval = publisher_period_ * minimumPublishIntervalRatio;
const auto elapsed_time = (current_time - last_published_time_).seconds();
if (elapsed_time < minimum_publish_interval) {
return;
Expand All @@ -236,7 +237,7 @@ void MultiObjectTracker::onTimer()

// if there was no update, publish if the elapsed time is longer than the maximum publish latency
// in this case, it will perform extrapolate/remove old objects
const double maximum_publish_interval = publisher_period_ * 1.05; // 105% of the period
const double maximum_publish_interval = publisher_period_ * maximumPublishIntervalRatio;
should_publish = should_publish || elapsed_time > maximum_publish_interval;

// Publish with delay compensation to the current time
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,8 @@ class MultiObjectTracker : public rclcpp::Node
rclcpp::Time last_published_time_;
rclcpp::Time last_updated_time_;
double publisher_period_;
static constexpr double minimum_publish_interval_ratio = 0.85;
static constexpr double maximum_publish_interval_ratio = 1.05;

// internal states
std::string world_frame_id_; // tracking frame
Expand Down

0 comments on commit ff8b646

Please sign in to comment.