Skip to content

Commit 1d40cf9

Browse files
committed
fix(tracker_object_merger): add sanity check for tracker merger (autowarefoundation#6386)
* feat: add time based sanity check in validation function Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * fix: do not skip update when objects are empty Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> --------- Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent f834da8 commit 1d40cf9

File tree

4 files changed

+11
-8
lines changed

4 files changed

+11
-8
lines changed

perception/tracking_object_merger/README.md

+2-2
Original file line numberDiff line numberDiff line change
@@ -59,8 +59,8 @@ We use the `existence_probability` to manage tracklet.
5959
- When we create a new tracklet, we set the `existence_probability` to $p_{sensor}$ value.
6060
- In each update with specific sensor, we set the `existence_probability` to $p_{sensor}$ value.
6161
- When tracklet does not have update with specific sensor, we reduce the `existence_probability` by `decay_rate`
62-
- Object can be published if `existence_probability` is larger than `publish_probability_threshold`
63-
- Object will be removed if `existence_probability` is smaller than `remove_probability_threshold`
62+
- Object can be published if `existence_probability` is larger than `publish_probability_threshold` and time from last update is smaller than `max_dt`
63+
- Object will be removed if `existence_probability` is smaller than `remove_probability_threshold` and time from last update is larger than `max_dt`
6464

6565
![tracklet_management](./image/tracklet_management.drawio.svg)
6666

perception/tracking_object_merger/include/tracking_object_merger/utils/tracker_state.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -118,7 +118,7 @@ class TrackerState
118118
std::function<void(TrackedObject &, const TrackedObject &)> update_func);
119119
// const functions
120120
bool hasUUID(const MEASUREMENT_STATE input, const unique_identifier_msgs::msg::UUID & uuid) const;
121-
bool isValid() const;
121+
bool isValid(const rclcpp::Time & current_time) const;
122122
bool canPublish() const;
123123
TrackedObject getObject() const;
124124

perception/tracking_object_merger/src/decorative_tracker_merger.cpp

-3
Original file line numberDiff line numberDiff line change
@@ -250,9 +250,6 @@ bool DecorativeTrackerMergerNode::decorativeMerger(
250250
{
251251
// get current time
252252
const auto current_time = rclcpp::Time(input_objects_msg->header.stamp);
253-
if (input_objects_msg->objects.empty()) {
254-
return false;
255-
}
256253
if (inner_tracker_objects_.empty()) {
257254
for (const auto & object : input_objects_msg->objects) {
258255
inner_tracker_objects_.push_back(createNewTracker(input_sensor, current_time, object));

perception/tracking_object_merger/src/utils/tracker_state.cpp

+8-2
Original file line numberDiff line numberDiff line change
@@ -271,8 +271,14 @@ bool TrackerState::hasUUID(
271271
return input_uuid_map_.at(input) == uuid;
272272
}
273273

274-
bool TrackerState::isValid() const
274+
bool TrackerState::isValid(const rclcpp::Time & current_time) const
275275
{
276+
// check dt from last update
277+
double dt = (current_time - last_update_time_).seconds();
278+
if (std::abs(dt) > max_dt_) {
279+
return false;
280+
}
281+
276282
// check if tracker state is valid
277283
if (existence_probability_ < remove_probability_threshold_) {
278284
return false;
@@ -302,7 +308,7 @@ TrackedObjects getTrackedObjectsFromTrackerStates(
302308
// sanitize and get tracked objects
303309
for (auto it = tracker_states.begin(); it != tracker_states.end();) {
304310
// check if tracker state is valid
305-
if (it->isValid()) {
311+
if (it->isValid(current_time)) {
306312
if (it->canPublish()) {
307313
// if valid, get tracked object
308314
tracked_objects.objects.push_back(it->getObject());

0 commit comments

Comments
 (0)