Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(autoware_multi_object_tracker): revert latency reduction logic and bring back to timer trigger #8277 #1436

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,6 @@ class MultiObjectTracker : public rclcpp::Node
// publish timer
rclcpp::TimerBase::SharedPtr publish_timer_;
rclcpp::Time last_published_time_;
double publisher_period_;

// internal states
std::string world_frame_id_; // tracking frame
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -153,9 +153,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
// If the delay compensation is enabled, the timer is used to publish the output at the correct
// time.
if (enable_delay_compensation) {
publisher_period_ = 1.0 / publish_rate; // [s]
constexpr double timer_multiplier = 20.0; // 20 times frequent for publish timing check
const auto timer_period = rclcpp::Rate(publish_rate * timer_multiplier).period();
const auto timer_period = rclcpp::Rate(publish_rate).period();
publish_timer_ = rclcpp::create_timer(
this, get_clock(), timer_period, std::bind(&MultiObjectTracker::onTimer, this));
}
Expand Down Expand Up @@ -210,35 +208,13 @@ void MultiObjectTracker::onTrigger()
std::vector<std::pair<uint, DetectedObjects>> objects_list;
const bool is_objects_ready = input_manager_->getObjects(current_time, objects_list);
if (!is_objects_ready) return;

onMessage(objects_list);
const rclcpp::Time latest_time(objects_list.back().second.header.stamp);

// Publish objects if the timer is not enabled
if (publish_timer_ == nullptr) {
// if the delay compensation is disabled, publish the objects in the latest time
publish(latest_time);
} else {
// Publish if the next publish time is close
const double minimum_publish_interval = publisher_period_ * 0.70; // 70% of the period
const rclcpp::Time publish_time = this->now();
if ((publish_time - last_published_time_).seconds() > minimum_publish_interval) {
checkAndPublish(publish_time);
}
}
}

void MultiObjectTracker::onTimer()
{
const rclcpp::Time current_time = this->now();

// Check the publish period
const auto elapsed_time = (current_time - last_published_time_).seconds();
// If the elapsed time is over the period, publish objects with prediction
constexpr double maximum_latency_ratio = 1.11; // 11% margin
const double maximum_publish_latency = publisher_period_ * maximum_latency_ratio;
if (elapsed_time < maximum_publish_latency) return;

// get objects from the input manager and run process
ObjectsList objects_list;
const bool is_objects_ready = input_manager_->getObjects(current_time, objects_list);
Expand Down
Loading