@@ -30,21 +30,10 @@ namespace autoware::multi_object_tracker
30
30
{
31
31
32
32
using Label = autoware_perception_msgs::msg::ObjectClassification;
33
+ using LabelType = autoware_perception_msgs::msg::ObjectClassification::_label_type;
33
34
34
- TrackerProcessor::TrackerProcessor (
35
- const std::map<std::uint8_t , std::string> & tracker_map, const size_t & channel_size)
36
- : tracker_map_(tracker_map), channel_size_(channel_size)
35
+ TrackerProcessor::TrackerProcessor (const TrackerProcessorConfig & config) : config_(config)
37
36
{
38
- // Set tracker lifetime parameters
39
- max_elapsed_time_ = 1.0 ; // [s]
40
-
41
- // Set tracker overlap remover parameters
42
- min_iou_ = 0.1 ; // [ratio]
43
- min_iou_for_unknown_object_ = 0.001 ; // [ratio]
44
- distance_threshold_ = 5.0 ; // [m]
45
-
46
- // Set tracker confidence threshold
47
- confident_count_threshold_ = 3 ; // [count]
48
37
}
49
38
50
39
void TrackerProcessor::predict (const rclcpp::Time & time)
@@ -95,34 +84,36 @@ std::shared_ptr<Tracker> TrackerProcessor::createNewTracker(
95
84
const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
96
85
const geometry_msgs::msg::Transform & self_transform, const uint & channel_index) const
97
86
{
98
- const std:: uint8_t label =
87
+ const LabelType label =
99
88
autoware::object_recognition_utils::getHighestProbLabel (object.classification );
100
- if (tracker_map_ .count (label) != 0 ) {
101
- const auto tracker = tracker_map_ .at (label);
89
+ if (config_. tracker_map .count (label) != 0 ) {
90
+ const auto tracker = config_. tracker_map .at (label);
102
91
if (tracker == " bicycle_tracker" )
103
92
return std::make_shared<BicycleTracker>(
104
- time , object, self_transform, channel_size_ , channel_index);
93
+ time , object, self_transform, config_. channel_size , channel_index);
105
94
if (tracker == " big_vehicle_tracker" )
106
95
return std::make_shared<VehicleTracker>(
107
- object_model::big_vehicle, time , object, self_transform, channel_size_, channel_index);
96
+ object_model::big_vehicle, time , object, self_transform, config_.channel_size ,
97
+ channel_index);
108
98
if (tracker == " multi_vehicle_tracker" )
109
99
return std::make_shared<MultipleVehicleTracker>(
110
- time , object, self_transform, channel_size_ , channel_index);
100
+ time , object, self_transform, config_. channel_size , channel_index);
111
101
if (tracker == " normal_vehicle_tracker" )
112
102
return std::make_shared<VehicleTracker>(
113
- object_model::normal_vehicle, time , object, self_transform, channel_size_, channel_index);
103
+ object_model::normal_vehicle, time , object, self_transform, config_.channel_size ,
104
+ channel_index);
114
105
if (tracker == " pass_through_tracker" )
115
106
return std::make_shared<PassThroughTracker>(
116
- time , object, self_transform, channel_size_ , channel_index);
107
+ time , object, self_transform, config_. channel_size , channel_index);
117
108
if (tracker == " pedestrian_and_bicycle_tracker" )
118
109
return std::make_shared<PedestrianAndBicycleTracker>(
119
- time , object, self_transform, channel_size_ , channel_index);
110
+ time , object, self_transform, config_. channel_size , channel_index);
120
111
if (tracker == " pedestrian_tracker" )
121
112
return std::make_shared<PedestrianTracker>(
122
- time , object, self_transform, channel_size_ , channel_index);
113
+ time , object, self_transform, config_. channel_size , channel_index);
123
114
}
124
115
return std::make_shared<UnknownTracker>(
125
- time , object, self_transform, channel_size_ , channel_index);
116
+ time , object, self_transform, config_. channel_size , channel_index);
126
117
}
127
118
128
119
void TrackerProcessor::prune (const rclcpp::Time & time)
@@ -137,7 +128,7 @@ void TrackerProcessor::removeOldTracker(const rclcpp::Time & time)
137
128
{
138
129
// Check elapsed time from last update
139
130
for (auto itr = list_tracker_.begin (); itr != list_tracker_.end (); ++itr) {
140
- const bool is_old = max_elapsed_time_ < (*itr)->getElapsedTimeFromLastUpdate (time );
131
+ const bool is_old = config_. tracker_lifetime < (*itr)->getElapsedTimeFromLastUpdate (time );
141
132
// If the tracker is old, delete it
142
133
if (is_old) {
143
134
auto erase_itr = itr;
@@ -168,7 +159,7 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time)
168
159
object2.kinematics .pose_with_covariance .pose .position .y );
169
160
170
161
// If the distance is too large, skip
171
- if (distance > distance_threshold_ ) {
162
+ if (distance > config_. distance_threshold ) {
172
163
continue ;
173
164
}
174
165
@@ -184,7 +175,7 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time)
184
175
// If both trackers are UNKNOWN, delete the younger tracker
185
176
// If one side of the tracker is UNKNOWN, delete UNKNOWN objects
186
177
if (label1 == Label::UNKNOWN || label2 == Label::UNKNOWN) {
187
- if (iou > min_iou_for_unknown_object_ ) {
178
+ if (iou > config_. min_unknown_object_removal_iou ) {
188
179
if (label1 == Label::UNKNOWN && label2 == Label::UNKNOWN) {
189
180
if ((*itr1)->getTotalMeasurementCount () < (*itr2)->getTotalMeasurementCount ()) {
190
181
should_delete_tracker1 = true ;
@@ -198,7 +189,7 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time)
198
189
}
199
190
}
200
191
} else { // If neither object is UNKNOWN, delete the younger tracker
201
- if (iou > min_iou_ ) {
192
+ if (iou > config_. min_known_object_removal_iou ) {
202
193
if ((*itr1)->getTotalMeasurementCount () < (*itr2)->getTotalMeasurementCount ()) {
203
194
should_delete_tracker1 = true ;
204
195
} else {
@@ -226,7 +217,8 @@ bool TrackerProcessor::isConfidentTracker(const std::shared_ptr<Tracker> & track
226
217
// Confidence is determined by counting the number of measurements.
227
218
// If the number of measurements is equal to or greater than the threshold, the tracker is
228
219
// considered confident.
229
- return tracker->getTotalMeasurementCount () >= confident_count_threshold_;
220
+ auto label = tracker->getHighestProbLabel ();
221
+ return tracker->getTotalMeasurementCount () >= config_.confident_count_threshold .at (label);
230
222
}
231
223
232
224
void TrackerProcessor::getTrackedObjects (
0 commit comments