Skip to content

Commit 35da6d8

Browse files
jakor97pre-commit-ci[bot]technolojin
authored
refactor(autoware_multi_object_tracker): add configurable tracker parameters (#9621)
* refactor(autoware_multi_object_tracker): add configurable tracker parameters Signed-off-by: jkoronczok <jkoronczok@autonomous-systems.pl> * style(pre-commit): autofix * refactor(autoware_multi_object_tracker): remove default values from parameter declarations Signed-off-by: jkoronczok <jkoronczok@autonomous-systems.pl> * refactor(autoware_multi_object_tracker): update schema file Signed-off-by: jkoronczok <jkoronczok@autonomous-systems.pl> * style(pre-commit): autofix * Update perception/autoware_multi_object_tracker/src/processor/processor.cpp * Update perception/autoware_multi_object_tracker/src/processor/processor.cpp --------- Signed-off-by: jkoronczok <jkoronczok@autonomous-systems.pl> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Taekjin LEE <technolojin@gmail.com>
1 parent 91984f8 commit 35da6d8

File tree

5 files changed

+152
-51
lines changed

5 files changed

+152
-51
lines changed

perception/autoware_multi_object_tracker/config/multi_object_tracker_node.param.yaml

+15
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,21 @@
1515
enable_delay_compensation: false
1616
consider_odometry_uncertainty: false
1717

18+
# tracker parameters
19+
tracker_lifetime: 1.0 # [s]
20+
min_known_object_removal_iou: 0.1 # [ratio]
21+
min_unknown_object_removal_iou: 0.001 # [ratio]
22+
distance_threshold: 5.0 # [m]
23+
confident_count_threshold:
24+
UNKNOWN: 3
25+
CAR: 3
26+
TRUCK: 3
27+
BUS: 3
28+
TRAILER: 3
29+
MOTORBIKE: 3
30+
BICYCLE: 3
31+
PEDESTRIAN: 3
32+
1833
# debug parameters
1934
publish_processing_time: false
2035
publish_tentative_objects: false

perception/autoware_multi_object_tracker/schema/multi_object_tracker_node.schema.json

+69
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,69 @@
5656
"description": "If True, tracker use timers to schedule publishers and use prediction step to extrapolate object state at desired timestamp.",
5757
"default": false
5858
},
59+
"consider_odometry_uncertainty": {
60+
"type": "boolean",
61+
"description": "If True, consider odometry uncertainty in tracking.",
62+
"default": false
63+
},
64+
"tracker_lifetime": {
65+
"type": "number",
66+
"description": "Lifetime of the tracker in seconds.",
67+
"default": 1.0
68+
},
69+
"min_known_object_removal_iou": {
70+
"type": "number",
71+
"description": "Minimum IOU between associated objects with known label to remove younger tracker",
72+
"default": 0.1
73+
},
74+
"min_unknown_object_removal_iou": {
75+
"type": "number",
76+
"description": "Minimum IOU between associated objects with unknown label to remove unknown tracker",
77+
"default": 0.001
78+
},
79+
"distance_threshold": {
80+
"type": "number",
81+
"description": "Distance threshold in meters.",
82+
"default": 5.0
83+
},
84+
"confident_count_threshold": {
85+
"type": "object",
86+
"properties": {
87+
"UNKNOWN": {
88+
"type": "number",
89+
"default": 3
90+
},
91+
"CAR": {
92+
"type": "number",
93+
"default": 3
94+
},
95+
"TRUCK": {
96+
"type": "number",
97+
"default": 3
98+
},
99+
"BUS": {
100+
"type": "number",
101+
"default": 3
102+
},
103+
"TRAILER": {
104+
"type": "number",
105+
"default": 3
106+
},
107+
"MOTORBIKE": {
108+
"type": "number",
109+
"default": 3
110+
},
111+
"BICYCLE": {
112+
"type": "number",
113+
"default": 3
114+
},
115+
"PEDESTRIAN": {
116+
"type": "number",
117+
"default": 3
118+
}
119+
},
120+
"description": "Number of measurements to consider tracker as confident for different object classes."
121+
},
59122
"publish_processing_time": {
60123
"type": "boolean",
61124
"description": "Enable to publish debug message of process time information.",
@@ -93,6 +156,12 @@
93156
"publish_rate",
94157
"world_frame_id",
95158
"enable_delay_compensation",
159+
"consider_odometry_uncertainty",
160+
"tracker_lifetime",
161+
"min_known_object_removal_iou",
162+
"min_unknown_object_removal_iou",
163+
"distance_threshold",
164+
"confident_count_threshold",
96165
"publish_processing_time",
97166
"publish_tentative_objects",
98167
"publish_debug_markers",

perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp

+32-10
Original file line numberDiff line numberDiff line change
@@ -64,12 +64,12 @@ boost::optional<geometry_msgs::msg::Transform> getTransformAnonymous(
6464
return boost::none;
6565
}
6666
}
67-
6867
} // namespace
6968

7069
namespace autoware::multi_object_tracker
7170
{
7271
using Label = autoware_perception_msgs::msg::ObjectClassification;
72+
using LabelType = autoware_perception_msgs::msg::ObjectClassification::_label_type;
7373

7474
MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
7575
: rclcpp::Node("multi_object_tracker", node_options),
@@ -166,23 +166,45 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
166166

167167
// Initialize processor
168168
{
169-
std::map<std::uint8_t, std::string> tracker_map;
170-
tracker_map.insert(
169+
TrackerProcessorConfig config;
170+
config.tracker_map.insert(
171171
std::make_pair(Label::CAR, this->declare_parameter<std::string>("car_tracker")));
172-
tracker_map.insert(
172+
config.tracker_map.insert(
173173
std::make_pair(Label::TRUCK, this->declare_parameter<std::string>("truck_tracker")));
174-
tracker_map.insert(
174+
config.tracker_map.insert(
175175
std::make_pair(Label::BUS, this->declare_parameter<std::string>("bus_tracker")));
176-
tracker_map.insert(
176+
config.tracker_map.insert(
177177
std::make_pair(Label::TRAILER, this->declare_parameter<std::string>("trailer_tracker")));
178-
tracker_map.insert(std::make_pair(
178+
config.tracker_map.insert(std::make_pair(
179179
Label::PEDESTRIAN, this->declare_parameter<std::string>("pedestrian_tracker")));
180-
tracker_map.insert(
180+
config.tracker_map.insert(
181181
std::make_pair(Label::BICYCLE, this->declare_parameter<std::string>("bicycle_tracker")));
182-
tracker_map.insert(std::make_pair(
182+
config.tracker_map.insert(std::make_pair(
183183
Label::MOTORCYCLE, this->declare_parameter<std::string>("motorcycle_tracker")));
184+
config.channel_size = input_channel_size_;
185+
186+
// Declare parameters
187+
config.tracker_lifetime = declare_parameter<double>("tracker_lifetime");
188+
config.min_known_object_removal_iou = declare_parameter<double>("min_known_object_removal_iou");
189+
config.min_unknown_object_removal_iou =
190+
declare_parameter<double>("min_unknown_object_removal_iou");
191+
config.distance_threshold = declare_parameter<double>("distance_threshold");
192+
193+
// Map from class name to label
194+
std::map<std::string, LabelType> class_name_to_label = {
195+
{"UNKNOWN", Label::UNKNOWN}, {"CAR", Label::CAR},
196+
{"TRUCK", Label::TRUCK}, {"BUS", Label::BUS},
197+
{"TRAILER", Label::TRAILER}, {"MOTORBIKE", Label::MOTORCYCLE},
198+
{"BICYCLE", Label::BICYCLE}, {"PEDESTRIAN", Label::PEDESTRIAN}};
199+
200+
// Declare parameters and initialize confident_count_threshold_map
201+
for (const auto & [class_name, class_label] : class_name_to_label) {
202+
int64_t value = declare_parameter<int64_t>("confident_count_threshold." + class_name);
203+
config.confident_count_threshold[class_label] = static_cast<int>(value);
204+
}
184205

185-
processor_ = std::make_unique<TrackerProcessor>(tracker_map, input_channel_size_);
206+
// Initialize processor with parameters
207+
processor_ = std::make_unique<TrackerProcessor>(config);
186208
}
187209

188210
// Data association initialization

perception/autoware_multi_object_tracker/src/processor/processor.cpp

+21-29
Original file line numberDiff line numberDiff line change
@@ -30,21 +30,10 @@ namespace autoware::multi_object_tracker
3030
{
3131

3232
using Label = autoware_perception_msgs::msg::ObjectClassification;
33+
using LabelType = autoware_perception_msgs::msg::ObjectClassification::_label_type;
3334

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)
3736
{
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]
4837
}
4938

5039
void TrackerProcessor::predict(const rclcpp::Time & time)
@@ -95,34 +84,36 @@ std::shared_ptr<Tracker> TrackerProcessor::createNewTracker(
9584
const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
9685
const geometry_msgs::msg::Transform & self_transform, const uint & channel_index) const
9786
{
98-
const std::uint8_t label =
87+
const LabelType label =
9988
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);
10291
if (tracker == "bicycle_tracker")
10392
return std::make_shared<BicycleTracker>(
104-
time, object, self_transform, channel_size_, channel_index);
93+
time, object, self_transform, config_.channel_size, channel_index);
10594
if (tracker == "big_vehicle_tracker")
10695
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);
10898
if (tracker == "multi_vehicle_tracker")
10999
return std::make_shared<MultipleVehicleTracker>(
110-
time, object, self_transform, channel_size_, channel_index);
100+
time, object, self_transform, config_.channel_size, channel_index);
111101
if (tracker == "normal_vehicle_tracker")
112102
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);
114105
if (tracker == "pass_through_tracker")
115106
return std::make_shared<PassThroughTracker>(
116-
time, object, self_transform, channel_size_, channel_index);
107+
time, object, self_transform, config_.channel_size, channel_index);
117108
if (tracker == "pedestrian_and_bicycle_tracker")
118109
return std::make_shared<PedestrianAndBicycleTracker>(
119-
time, object, self_transform, channel_size_, channel_index);
110+
time, object, self_transform, config_.channel_size, channel_index);
120111
if (tracker == "pedestrian_tracker")
121112
return std::make_shared<PedestrianTracker>(
122-
time, object, self_transform, channel_size_, channel_index);
113+
time, object, self_transform, config_.channel_size, channel_index);
123114
}
124115
return std::make_shared<UnknownTracker>(
125-
time, object, self_transform, channel_size_, channel_index);
116+
time, object, self_transform, config_.channel_size, channel_index);
126117
}
127118

128119
void TrackerProcessor::prune(const rclcpp::Time & time)
@@ -137,7 +128,7 @@ void TrackerProcessor::removeOldTracker(const rclcpp::Time & time)
137128
{
138129
// Check elapsed time from last update
139130
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);
141132
// If the tracker is old, delete it
142133
if (is_old) {
143134
auto erase_itr = itr;
@@ -168,7 +159,7 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time)
168159
object2.kinematics.pose_with_covariance.pose.position.y);
169160

170161
// If the distance is too large, skip
171-
if (distance > distance_threshold_) {
162+
if (distance > config_.distance_threshold) {
172163
continue;
173164
}
174165

@@ -184,7 +175,7 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time)
184175
// If both trackers are UNKNOWN, delete the younger tracker
185176
// If one side of the tracker is UNKNOWN, delete UNKNOWN objects
186177
if (label1 == Label::UNKNOWN || label2 == Label::UNKNOWN) {
187-
if (iou > min_iou_for_unknown_object_) {
178+
if (iou > config_.min_unknown_object_removal_iou) {
188179
if (label1 == Label::UNKNOWN && label2 == Label::UNKNOWN) {
189180
if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) {
190181
should_delete_tracker1 = true;
@@ -198,7 +189,7 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time)
198189
}
199190
}
200191
} else { // If neither object is UNKNOWN, delete the younger tracker
201-
if (iou > min_iou_) {
192+
if (iou > config_.min_known_object_removal_iou) {
202193
if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) {
203194
should_delete_tracker1 = true;
204195
} else {
@@ -226,7 +217,8 @@ bool TrackerProcessor::isConfidentTracker(const std::shared_ptr<Tracker> & track
226217
// Confidence is determined by counting the number of measurements.
227218
// If the number of measurements is equal to or greater than the threshold, the tracker is
228219
// considered confident.
229-
return tracker->getTotalMeasurementCount() >= confident_count_threshold_;
220+
auto label = tracker->getHighestProbLabel();
221+
return tracker->getTotalMeasurementCount() >= config_.confident_count_threshold.at(label);
230222
}
231223

232224
void TrackerProcessor::getTrackedObjects(

perception/autoware_multi_object_tracker/src/processor/processor.hpp

+15-12
Original file line numberDiff line numberDiff line change
@@ -31,11 +31,23 @@
3131

3232
namespace autoware::multi_object_tracker
3333
{
34+
using LabelType = autoware_perception_msgs::msg::ObjectClassification::_label_type;
35+
36+
struct TrackerProcessorConfig
37+
{
38+
std::map<LabelType, std::string> tracker_map;
39+
size_t channel_size;
40+
float tracker_lifetime; // [s]
41+
float min_known_object_removal_iou; // ratio [0, 1]
42+
float min_unknown_object_removal_iou; // ratio [0, 1]
43+
double distance_threshold; // [m]
44+
std::map<LabelType, int> confident_count_threshold; // [count]
45+
};
46+
3447
class TrackerProcessor
3548
{
3649
public:
37-
explicit TrackerProcessor(
38-
const std::map<std::uint8_t, std::string> & tracker_map, const size_t & channel_size);
50+
explicit TrackerProcessor(const TrackerProcessorConfig & config);
3951

4052
const std::list<std::shared_ptr<Tracker>> & getListTracker() const { return list_tracker_; }
4153
// tracker processes
@@ -62,17 +74,8 @@ class TrackerProcessor
6274
void getExistenceProbabilities(std::vector<std::vector<float>> & existence_vectors) const;
6375

6476
private:
65-
std::map<std::uint8_t, std::string> tracker_map_;
77+
TrackerProcessorConfig config_;
6678
std::list<std::shared_ptr<Tracker>> list_tracker_;
67-
const size_t channel_size_;
68-
69-
// parameters
70-
float max_elapsed_time_; // [s]
71-
float min_iou_; // [ratio]
72-
float min_iou_for_unknown_object_; // [ratio]
73-
double distance_threshold_; // [m]
74-
int confident_count_threshold_; // [count]
75-
7679
void removeOldTracker(const rclcpp::Time & time);
7780
void removeOverlappedTracker(const rclcpp::Time & time);
7881
std::shared_ptr<Tracker> createNewTracker(

0 commit comments

Comments
 (0)