Skip to content

Commit ddc1ec1

Browse files
committed
feat(multi_object_tracker): reduce publish delay (autowarefoundation#6710)
* feat: implement a new publish timer Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * chore: add comments for new variables Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * fix: variable name was wrong Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> fix: reduce lower limit of publish interval Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> fix: enlarge publish range upper limit Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> fix: set parameter tested and agreed Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> --------- Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent ef80be4 commit ddc1ec1

File tree

2 files changed

+41
-17
lines changed

2 files changed

+41
-17
lines changed

perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp

+7-3
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,11 @@ class MultiObjectTracker : public rclcpp::Node
5858
tracked_objects_pub_;
5959
rclcpp::Subscription<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr
6060
detected_object_sub_;
61-
rclcpp::TimerBase::SharedPtr publish_timer_; // publish timer
61+
62+
// publish timer
63+
rclcpp::TimerBase::SharedPtr publish_timer_;
64+
rclcpp::Time last_published_time_;
65+
double publisher_period_;
6266

6367
// debugger class
6468
std::unique_ptr<TrackerDebugger> debugger_;
@@ -79,14 +83,14 @@ class MultiObjectTracker : public rclcpp::Node
7983
std::unique_ptr<DataAssociation> data_association_;
8084

8185
void checkTrackerLifeCycle(
82-
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time,
83-
const geometry_msgs::msg::Transform & self_transform);
86+
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time);
8487
void sanitizeTracker(
8588
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time);
8689
std::shared_ptr<Tracker> createNewTracker(
8790
const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
8891
const geometry_msgs::msg::Transform & self_transform) const;
8992

93+
void checkAndPublish(const rclcpp::Time & time);
9094
void publish(const rclcpp::Time & time) const;
9195
inline bool shouldTrackerPublish(const std::shared_ptr<const Tracker> tracker) const;
9296
};

perception/multi_object_tracker/src/multi_object_tracker_core.cpp

+34-14
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,7 @@ boost::optional<geometry_msgs::msg::Transform> getTransformAnonymous(
6868

6969
MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
7070
: rclcpp::Node("multi_object_tracker", node_options),
71+
last_published_time_(this->now()),
7172
tf_buffer_(this->get_clock()),
7273
tf_listener_(tf_buffer_)
7374
{
@@ -83,7 +84,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
8384
create_publisher<autoware_auto_perception_msgs::msg::TrackedObjects>("output", rclcpp::QoS{1});
8485

8586
// Parameters
86-
double publish_rate = declare_parameter<double>("publish_rate");
87+
double publish_rate = declare_parameter<double>("publish_rate"); // [hz]
8788
world_frame_id_ = declare_parameter<std::string>("world_frame_id");
8889
bool enable_delay_compensation{declare_parameter<bool>("enable_delay_compensation")};
8990

@@ -94,11 +95,15 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
9495
this->get_node_base_interface(), this->get_node_timers_interface());
9596
tf_buffer_.setCreateTimerInterface(cti);
9697

97-
// Create ROS time based timer
98+
// Create ROS time based timer.
99+
// If the delay compensation is enabled, the timer is used to publish the output at the correct
100+
// time.
98101
if (enable_delay_compensation) {
99-
const auto period_ns = rclcpp::Rate(publish_rate).period();
102+
publisher_period_ = 1.0 / publish_rate; // [s]
103+
constexpr double timer_multiplier = 20.0; // 20 times frequent for publish timing check
104+
const auto timer_period = rclcpp::Rate(publish_rate * timer_multiplier).period();
100105
publish_timer_ = rclcpp::create_timer(
101-
this, get_clock(), period_ns, std::bind(&MultiObjectTracker::onTimer, this));
106+
this, get_clock(), timer_period, std::bind(&MultiObjectTracker::onTimer, this));
102107
}
103108

104109
const auto tmp = this->declare_parameter<std::vector<int64_t>>("can_assign_matrix");
@@ -179,7 +184,7 @@ void MultiObjectTracker::onMeasurement(
179184
}
180185

181186
/* life cycle check */
182-
checkTrackerLifeCycle(list_tracker_, measurement_time, *self_transform);
187+
checkTrackerLifeCycle(list_tracker_, measurement_time);
183188
/* sanitize trackers */
184189
sanitizeTracker(list_tracker_, measurement_time);
185190

@@ -198,7 +203,14 @@ void MultiObjectTracker::onMeasurement(
198203

199204
// Publish objects if the timer is not enabled
200205
if (publish_timer_ == nullptr) {
206+
// Publish if the delay compensation is disabled
201207
publish(measurement_time);
208+
} else {
209+
// Publish if the next publish time is close
210+
const double minimum_publish_interval = publisher_period_ * 0.70; // 70% of the period
211+
if ((this->now() - last_published_time_).seconds() > minimum_publish_interval) {
212+
checkAndPublish(this->now());
213+
}
202214
}
203215
}
204216

@@ -232,24 +244,32 @@ std::shared_ptr<Tracker> MultiObjectTracker::createNewTracker(
232244
void MultiObjectTracker::onTimer()
233245
{
234246
const rclcpp::Time current_time = this->now();
235-
const auto self_transform =
236-
getTransformAnonymous(tf_buffer_, world_frame_id_, "base_link", current_time);
237-
if (!self_transform) {
238-
return;
247+
// check the publish period
248+
const auto elapsed_time = (current_time - last_published_time_).seconds();
249+
// if the elapsed time is over the period, publish objects with prediction
250+
constexpr double maximum_latency_ratio = 1.11; // 11% margin
251+
const double maximum_publish_latency = publisher_period_ * maximum_latency_ratio;
252+
if (elapsed_time > maximum_publish_latency) {
253+
checkAndPublish(current_time);
239254
}
255+
}
240256

257+
void MultiObjectTracker::checkAndPublish(const rclcpp::Time & time)
258+
{
241259
/* life cycle check */
242-
checkTrackerLifeCycle(list_tracker_, current_time, *self_transform);
260+
checkTrackerLifeCycle(list_tracker_, time);
243261
/* sanitize trackers */
244-
sanitizeTracker(list_tracker_, current_time);
262+
sanitizeTracker(list_tracker_, time);
245263

246264
// Publish
247-
publish(current_time);
265+
publish(time);
266+
267+
// Update last published time
268+
last_published_time_ = this->now();
248269
}
249270

250271
void MultiObjectTracker::checkTrackerLifeCycle(
251-
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time,
252-
[[maybe_unused]] const geometry_msgs::msg::Transform & self_transform)
272+
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time)
253273
{
254274
/* params */
255275
constexpr float max_elapsed_time = 1.0;

0 commit comments

Comments
 (0)