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

feat(autoware_multi_object_tracker): reduce trigger latency #8657

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 @@ -73,7 +73,8 @@
: rclcpp::Node("multi_object_tracker", node_options),
tf_buffer_(this->get_clock()),
tf_listener_(tf_buffer_),
last_published_time_(this->now())
last_published_time_(this->now()),
last_updated_time_(this->now())

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp#L76-L77

Added lines #L76 - L77 were not covered by tests
{
// glog for debug
if (!google::IsGoogleLoggingInitialized()) {
Expand Down Expand Up @@ -153,7 +154,9 @@
// If the delay compensation is enabled, the timer is used to publish the output at the correct
// time.
if (enable_delay_compensation) {
const auto timer_period = rclcpp::Rate(publish_rate).period();
publisher_period_ = 1.0 / publish_rate; // [s]

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp#L157

Added line #L157 was not covered by tests
constexpr double timer_multiplier = 10.0; // 10 times frequent for publish timing check
const auto timer_period = rclcpp::Rate(publish_rate * timer_multiplier).period();

Check warning on line 159 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.

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp#L159

Added line #L159 was not covered by tests
publish_timer_ = rclcpp::create_timer(
this, get_clock(), timer_period, std::bind(&MultiObjectTracker::onTimer, this));
}
Expand Down Expand Up @@ -221,21 +224,30 @@
{
const rclcpp::Time current_time = this->now();

// get objects from the input manager and run process
ObjectsList objects_list;
const bool is_objects_ready = input_manager_->getObjects(current_time, objects_list);
if (is_objects_ready) {
onMessage(objects_list);
// ensure minimum interval: room for the next process(prediction)
const double minimum_publish_interval = publisher_period_ * minimum_publish_interval_ratio;
const auto elapsed_time = (current_time - last_published_time_).seconds();

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp#L228-L229

Added lines #L228 - L229 were not covered by tests
if (elapsed_time < minimum_publish_interval) {
return;
}

// Publish with delay compensation
checkAndPublish(current_time);
// if there was update after publishing, publish new messages
bool should_publish = last_published_time_ < last_updated_time_;

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp#L235

Added line #L235 was not covered by tests

// 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_ * maximum_publish_interval_ratio;
should_publish = should_publish || elapsed_time > maximum_publish_interval;

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp#L239-L240

Added lines #L239 - L240 were not covered by tests

// Publish with delay compensation to the current time
if (should_publish) checkAndPublish(current_time);
}

void MultiObjectTracker::onMessage(const ObjectsList & objects_list)
{
const rclcpp::Time current_time = this->now();
const rclcpp::Time oldest_time(objects_list.front().second.header.stamp);
last_updated_time_ = current_time;

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp#L250

Added line #L250 was not covered by tests

// process start
debugger_->startMeasurementTime(this->now(), oldest_time);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,10 @@ class MultiObjectTracker : public rclcpp::Node
// publish timer
rclcpp::TimerBase::SharedPtr publish_timer_;
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
Loading