Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
multiple_object_tracker_component.cpp
Go to the documentation of this file.
1// Copyright 2023 Leidos
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
16
17#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
18#include <units.h>
19#include <rclcpp/rclcpp.hpp>
20#include <rclcpp_components/register_node_macro.hpp>
21
22#include <algorithm>
23#include <chrono>
24#include <limits>
25#include <multiple_object_tracking/clustering.hpp>
26#include <multiple_object_tracking/ctra_model.hpp>
27#include <multiple_object_tracking/ctrv_model.hpp>
28#include <multiple_object_tracking/fusing.hpp>
29#include <multiple_object_tracking/gating.hpp>
30#include <multiple_object_tracking/scoring.hpp>
31#include <multiple_object_tracking/temporal_alignment.hpp>
32#include <unordered_map>
33#include <utility>
34#include <vector>
35
37{
38
39namespace mot = multiple_object_tracking;
40
41auto make_semantic_class(std::size_t numeric_value)
42{
43 switch (numeric_value) {
44 case 0:
45 return mot::SemanticClass::kUnknown;
46 case 1:
47 return mot::SemanticClass::kSmallVehicle;
48 case 2:
49 return mot::SemanticClass::kLargeVehicle;
50 case 3:
51 return mot::SemanticClass::kPedestrian;
52 case 4:
53 return mot::SemanticClass::kMotorcycle;
54 }
55
56 return mot::SemanticClass::kUnknown;
57}
58
59auto semantic_class_to_numeric_value(mot::SemanticClass semantic_class)
60{
61 switch (semantic_class) {
62 case mot::SemanticClass::kUnknown:
63 return 0;
64 case mot::SemanticClass::kSmallVehicle:
65 return 1;
66 case mot::SemanticClass::kLargeVehicle:
67 return 2;
68 case mot::SemanticClass::kPedestrian:
69 return 3;
70 case mot::SemanticClass::kMotorcycle:
71 return 4;
72 }
73
74 return 0;
75}
76
78 -> Detection
79{
80 const auto timestamp{
81 units::time::second_t{static_cast<double>(msg.header.stamp.sec)} +
82 units::time::nanosecond_t{static_cast<double>(msg.header.stamp.nanosec)}};
83
84 tf2::Quaternion orientation;
85 orientation.setX(msg.pose.pose.orientation.x);
86 orientation.setY(msg.pose.pose.orientation.y);
87 orientation.setZ(msg.pose.pose.orientation.z);
88 orientation.setW(msg.pose.pose.orientation.w);
89
90 double roll{0.0};
91 double pitch{0.0};
92 double yaw{0.0};
93
94 tf2::Matrix3x3 matrix{orientation};
95 matrix.getRPY(roll, pitch, yaw);
96
97 const mot::CtrvState state{
98 units::length::meter_t{msg.pose.pose.position.x},
99 units::length::meter_t{msg.pose.pose.position.y},
100 units::velocity::meters_per_second_t{msg.twist.twist.linear.x},
101 mot::Angle{units::angle::radian_t{yaw}},
102 units::angular_velocity::radians_per_second_t{msg.twist.twist.angular.z}};
103
104 mot::CtrvStateCovariance covariance = mot::CtrvStateCovariance::Zero();
105 covariance(0, 0) = msg.pose.covariance.at(0);
106 covariance(1, 1) = msg.pose.covariance.at(7);
107 covariance(2, 2) = msg.twist.covariance.at(0);
108 covariance(3, 3) = msg.pose.covariance.at(35);
109 covariance(4, 4) = msg.twist.covariance.at(35);
110
111 return mot::CtrvDetection{
112 timestamp, state, covariance, mot::Uuid{msg.id}, make_semantic_class(msg.semantic_class)};
113}
114
116 -> Detection
117{
118 const auto timestamp{
119 units::time::second_t{static_cast<double>(msg.header.stamp.sec)} +
120 units::time::nanosecond_t{static_cast<double>(msg.header.stamp.nanosec)}};
121
122 tf2::Quaternion orientation;
123 orientation.setX(msg.pose.pose.orientation.x);
124 orientation.setY(msg.pose.pose.orientation.y);
125 orientation.setZ(msg.pose.pose.orientation.z);
126 orientation.setW(msg.pose.pose.orientation.w);
127
128 double roll{0.0};
129 double pitch{0.0};
130 double yaw{0.0};
131
132 tf2::Matrix3x3 matrix{orientation};
133 matrix.getRPY(roll, pitch, yaw);
134
135 const mot::CtraState state{
136 units::length::meter_t{msg.pose.pose.position.x},
137 units::length::meter_t{msg.pose.pose.position.y},
138 units::velocity::meters_per_second_t{msg.twist.twist.linear.x},
139 mot::Angle{units::angle::radian_t{yaw}},
140 units::angular_velocity::radians_per_second_t{msg.twist.twist.angular.z},
141 units::acceleration::meters_per_second_squared_t{msg.accel.accel.linear.x}};
142
143 mot::CtraStateCovariance covariance = mot::CtraStateCovariance::Zero();
144 covariance(0, 0) = msg.pose.covariance.at(0);
145 covariance(1, 1) = msg.pose.covariance.at(7);
146 covariance(2, 2) = msg.twist.covariance.at(0);
147 covariance(3, 3) = msg.pose.covariance.at(35);
148 covariance(4, 4) = msg.twist.covariance.at(35);
149 covariance(5, 5) = msg.accel.covariance.at(0);
150
151 return mot::CtraDetection{
152 timestamp, state, covariance, mot::Uuid{msg.id}, make_semantic_class(msg.semantic_class)};
153}
154
156 -> Detection
157{
158 switch (msg.motion_model) {
159 case msg.MOTION_MODEL_CTRV:
160 return make_ctrv_detection(msg);
161
162 case msg.MOTION_MODEL_CTRA:
163 return make_ctra_detection(msg);
164
165 case msg.MOTION_MODEL_CV:
166 throw std::runtime_error("unsupported motion model type '3: constant velocity (CV)'");
167 }
168
169 throw std::runtime_error("unkown motion model type '" + std::to_string(msg.motion_model) + "'");
170}
171
172static auto to_ros_msg(const mot::CtraTrack & track)
173{
175
176 msg.header.stamp.sec = mot::remove_units(units::math::floor(track.timestamp));
177 msg.header.stamp.nanosec = mot::remove_units(
178 units::time::nanosecond_t{units::math::fmod(track.timestamp, units::time::second_t{1.0})});
179 msg.header.frame_id = "map";
180
181 msg.id = track.uuid.value();
182 msg.motion_model = msg.MOTION_MODEL_CTRA;
183 msg.pose.pose.position.x = mot::remove_units(track.state.position_x);
184 msg.pose.pose.position.y = mot::remove_units(track.state.position_y);
185
186 tf2::Quaternion orientation;
187 orientation.setRPY(0, 0, mot::remove_units(track.state.yaw.get_angle()));
188 msg.pose.pose.orientation.x = orientation.getX();
189 msg.pose.pose.orientation.y = orientation.getY();
190 msg.pose.pose.orientation.z = orientation.getZ();
191 msg.pose.pose.orientation.w = orientation.getW();
192
193 msg.twist.twist.linear.x = mot::remove_units(track.state.velocity);
194 msg.twist.twist.angular.z = mot::remove_units(track.state.yaw_rate);
195
196 msg.accel.accel.linear.x = mot::remove_units(track.state.acceleration);
197
198 msg.semantic_class = semantic_class_to_numeric_value(mot::get_semantic_class(track));
199
200 return msg;
201}
202
203static auto to_ros_msg(const mot::CtrvTrack & track)
204{
206
207 msg.header.stamp.sec = mot::remove_units(units::math::floor(track.timestamp));
208 msg.header.stamp.nanosec = mot::remove_units(
209 units::time::nanosecond_t{units::math::fmod(track.timestamp, units::time::second_t{1.0})});
210 msg.header.frame_id = "map";
211
212 msg.id = track.uuid.value();
213 msg.motion_model = msg.MOTION_MODEL_CTRV;
214 msg.pose.pose.position.x = mot::remove_units(track.state.position_x);
215 msg.pose.pose.position.y = mot::remove_units(track.state.position_y);
216
217 tf2::Quaternion orientation;
218 orientation.setRPY(0, 0, mot::remove_units(track.state.yaw.get_angle()));
219 msg.pose.pose.orientation.x = orientation.getX();
220 msg.pose.pose.orientation.y = orientation.getY();
221 msg.pose.pose.orientation.z = orientation.getZ();
222 msg.pose.pose.orientation.w = orientation.getW();
223
224 msg.twist.twist.linear.x = mot::remove_units(track.state.velocity);
225 msg.twist.twist.angular.z = mot::remove_units(track.state.yaw_rate);
226
227 msg.semantic_class = semantic_class_to_numeric_value(mot::get_semantic_class(track));
228
229 return msg;
230}
231
232static auto to_ros_msg(const Track & track)
233{
234 static constexpr mot::Visitor visitor{
235 [](const mot::CtrvTrack & t) { return to_ros_msg(t); },
236 [](const mot::CtraTrack & t) { return to_ros_msg(t); },
237 [](const auto &) {
238 // Currently on support CTRV and CTRA
239 throw std::runtime_error{"cannot make ROS 2 message from track type"};
240 }};
241
242 return std::visit(visitor, track);
243}
244
246: CarmaLifecycleNode{options}
247{
248}
249
251 const rclcpp_lifecycle::State & /* previous_state */) -> carma_ros2_utils::CallbackReturn
252{
253 RCLCPP_INFO(get_logger(), "Lifecycle transition: configuring");
254
255 track_list_pub_ = create_publisher<carma_cooperative_perception_interfaces::msg::TrackList>(
256 "output/track_list", 1);
257
258 detection_list_sub_ = create_subscription<
259 carma_cooperative_perception_interfaces::msg::DetectionList>(
260 "input/detection_list", 1,
261 [this](const carma_cooperative_perception_interfaces::msg::DetectionList::SharedPtr msg_ptr) {
262 if (const auto current_state{this->get_current_state().label()}; current_state == "active") {
263 this->store_new_detections(*msg_ptr);
264 } else {
265 RCLCPP_WARN(
266 this->get_logger(),
267 "Trying to receive message on the topic '%s', but the containing node is not activated. "
268 "Current node state: '%s'",
269 this->detection_list_sub_->get_topic_name(), current_state.c_str());
270 }
271 });
272
273 on_set_parameters_callback_ =
274 add_on_set_parameters_callback([this](const std::vector<rclcpp::Parameter> & parameters) {
275 rcl_interfaces::msg::SetParametersResult result;
276 result.successful = true;
277 result.reason = "success";
278
279 for (const auto & parameter : parameters) {
280 if (parameter.get_name() == "execution_frequency_hz") {
281 if (this->get_current_state().label() == "active") {
282 result.successful = false;
283 result.reason = "parameter is read-only while node is in 'Active' state";
284
285 RCLCPP_ERROR(
286 get_logger(), "Cannot change parameter 'execution_frequency_hz': " + result.reason);
287
288 break;
289 } else {
290 this->execution_period_ = 1 / units::frequency::hertz_t{parameter.as_double()};
291 }
292 } else if (parameter.get_name() == "track_promotion_threshold") {
293 if (this->get_current_state().label() == "active") {
294 result.successful = false;
295 result.reason = "parameter is read-only while node is in 'Active' state";
296
297 RCLCPP_ERROR(
298 get_logger(), "Cannot change parameter 'execution_frequency_hz': " + result.reason);
299
300 break;
301 } else {
302 if (const auto value{parameter.as_int()}; value < 0) {
303 result.successful = false;
304 result.reason = "parameter must be nonnegative";
305 } else {
306 this->track_manager_.set_promotion_threshold_and_update(
307 mot::PromotionThreshold{static_cast<std::size_t>(value)});
308 }
309 }
310 } else if (parameter.get_name() == "track_removal_threshold") {
311 if (this->get_current_state().label() == "active") {
312 result.successful = false;
313 result.reason = "parameter is read-only while node is in 'Active' state";
314
315 RCLCPP_ERROR(
316 get_logger(), "Cannot change parameter 'execution_frequency_hz': " + result.reason);
317
318 break;
319 } else {
320 if (const auto value{parameter.as_int()}; value < 0) {
321 result.successful = false;
322 result.reason = "parameter must be nonnegative";
323 } else {
324 this->track_manager_.set_removal_threshold_and_update(
325 mot::RemovalThreshold{static_cast<std::size_t>(value)});
326 }
327 }
328 } else {
329 result.successful = false;
330 result.reason = "Unexpected parameter name '" + parameter.get_name() + '\'';
331 }
332 }
333
334 return result;
335 });
336
337 declare_parameter(
338 "execution_frequency_hz", mot::remove_units(units::frequency::hertz_t{1 / execution_period_}));
339
340 declare_parameter(
341 "track_promotion_threshold", static_cast<int>(track_manager_.get_promotion_threshold().value));
342
343 declare_parameter(
344 "track_removal_threshold", static_cast<int>(track_manager_.get_promotion_threshold().value));
345
346 RCLCPP_INFO(get_logger(), "Lifecycle transition: successfully configured");
347
348 return carma_ros2_utils::CallbackReturn::SUCCESS;
349}
350
351auto MultipleObjectTrackerNode::handle_on_activate(
352 const rclcpp_lifecycle::State & /* previous_state */) -> carma_ros2_utils::CallbackReturn
353{
354 RCLCPP_INFO(get_logger(), "Lifecycle transition: activating");
355
356 if (pipeline_execution_timer_ != nullptr) {
357 // The user might have changed the timer period since last time the Node was active
358 pipeline_execution_timer_->reset();
359 }
360
361 const std::chrono::duration<double, std::nano> period_ns{mot::remove_units(execution_period_)};
362 pipeline_execution_timer_ =
363 rclcpp::create_timer(this, this->get_clock(), period_ns, [this] { execute_pipeline(); });
364
365 RCLCPP_INFO(get_logger(), "Lifecycle transition: successfully activated");
366
367 return carma_ros2_utils::CallbackReturn::SUCCESS;
368}
369
370auto MultipleObjectTrackerNode::handle_on_deactivate(
371 const rclcpp_lifecycle::State & /* previous_state */) -> carma_ros2_utils::CallbackReturn
372{
373 RCLCPP_INFO(get_logger(), "Lifecycle transition: deactivating");
374
375 // There is currently no way to change a timer's period in ROS 2, so we will
376 // have to create a new one in case a user changes the period.
377 pipeline_execution_timer_.reset();
378
379 RCLCPP_INFO(get_logger(), "Lifecycle transition: successfully deactivated");
380
381 return carma_ros2_utils::CallbackReturn::SUCCESS;
382}
383
384auto MultipleObjectTrackerNode::handle_on_cleanup(
385 const rclcpp_lifecycle::State & /* previous_state */) -> carma_ros2_utils::CallbackReturn
386{
387 RCLCPP_INFO(get_logger(), "Lifecycle transition: cleaning up");
388
389 // CarmaLifecycleNode does not handle subscriber pointer reseting for us
390 detection_list_sub_.reset();
391
392 undeclare_parameter("execution_frequency_hz");
393 remove_on_set_parameters_callback(on_set_parameters_callback_.get());
394
395 RCLCPP_INFO(get_logger(), "Lifecycle transition: successfully cleaned up");
396
397 return carma_ros2_utils::CallbackReturn::SUCCESS;
398}
399
400auto MultipleObjectTrackerNode::handle_on_shutdown(
401 const rclcpp_lifecycle::State & /* previous_state */) -> carma_ros2_utils::CallbackReturn
402{
403 RCLCPP_INFO(get_logger(), "Lifecycle transition: shutting down");
404
405 // CarmaLifecycleNode does not handle subscriber pointer reseting for us
406 detection_list_sub_.reset();
407
408 RCLCPP_INFO(get_logger(), "Lifecycle transition: successfully shut down");
409
410 return carma_ros2_utils::CallbackReturn::SUCCESS;
411}
412
413auto MultipleObjectTrackerNode::store_new_detections(
414 const carma_cooperative_perception_interfaces::msg::DetectionList & msg) -> void
415{
416 if (std::size(msg.detections) == 0) {
417 RCLCPP_WARN(this->get_logger(), "Not storing detections: incoming detection list is empty");
418 return;
419 }
420
421 for (const auto & detection_msg : msg.detections) {
422 try {
423 const auto detection{make_detection(detection_msg)};
424 const auto uuid{mot::get_uuid(detection)};
425
426 if (uuid_index_map_.count(uuid) == 0) {
427 detections_.push_back(std::move(detection));
428 uuid_index_map_[uuid] = std::size(detections_) - 1;
429 } else {
430 RCLCPP_WARN_STREAM(
431 this->get_logger(),
432 "Detection with ID '" << uuid << "' already exists. Overwriting its data");
433 detections_.at(uuid_index_map_[uuid]) = detection;
434 }
435 } catch (const std::runtime_error & error) {
436 RCLCPP_ERROR(
437 this->get_logger(), "Ignoring detection with ID '%s': %s", detection_msg.id.c_str(),
438 error.what());
439 }
440 }
441}
442
444 std::vector<Detection> & detections, units::time::second_t end_time) -> void
445{
446 for (auto & detection : detections) {
447 mot::propagate_to_time(detection, end_time, mot::default_unscented_transform);
448 }
449}
450
451static auto predict_track_states(std::vector<Track> tracks, units::time::second_t end_time)
452{
453 for (auto & track : tracks) {
454 mot::propagate_to_time(track, end_time, mot::default_unscented_transform);
455 }
456
457 return tracks;
458}
459
468{
469 template <typename Track, typename Detection>
470 auto operator()(const Track & track, const Detection & detection) const -> std::optional<float>
471 {
472 if constexpr (std::is_same_v<decltype(track.state), decltype(detection.state)>) {
473 const auto dist{two_dimensional_distance(track.state, detection.state)};
474
475 // Fall back to 2D Euclidean distance if either semantic class if unknown. The unknown
476 // track/detection may actually be the same other track/detection we are scoring against.
477 if (
478 track.semantic_class == mot::SemanticClass::kUnknown ||
479 detection.semantic_class == mot::SemanticClass::kUnknown) {
480 return dist;
481 }
482
483 if (track.semantic_class == detection.semantic_class) {
484 return dist;
485 }
486 }
487
488 return std::nullopt;
489 }
490
491 template <typename... TrackAlternatives, typename... DetectionAlternatives>
493 const std::variant<TrackAlternatives...> & track,
494 const std::variant<DetectionAlternatives...> & detection) const -> std::optional<float>
495 {
496 return std::visit(
497 [this](const auto & t, const auto & d) { return (*this)(t, d); }, track, detection);
498 }
499
500private:
501 static auto two_dimensional_distance(const mot::CtrvState & lhs, const mot::CtrvState & rhs)
502 -> float
503 {
504 const auto x_diff_sq{
505 std::pow(mot::remove_units(lhs.position_x) - mot::remove_units(rhs.position_x), 2)};
506 const auto y_diff_sq{
507 std::pow(mot::remove_units(lhs.position_y) - mot::remove_units(rhs.position_y), 2)};
508
509 return std::sqrt(x_diff_sq + y_diff_sq);
510 }
511
512 static auto two_dimensional_distance(const mot::CtraState & lhs, const mot::CtraState & rhs)
513 -> float
514 {
515 const auto x_diff_sq{
516 std::pow(mot::remove_units(lhs.position_x) - mot::remove_units(rhs.position_x), 2)};
517 const auto y_diff_sq{
518 std::pow(mot::remove_units(lhs.position_y) - mot::remove_units(rhs.position_y), 2)};
519
520 return std::sqrt(x_diff_sq + y_diff_sq);
521 }
522};
523
528{
529 template <typename Detection>
530 auto operator()(const mot::Point & point, const Detection & detection) const -> double
531 {
532 double sum{0};
533
534 sum += std::pow(mot::remove_units(point.position_x - detection.state.position_x), 2);
535 sum += std::pow(mot::remove_units(point.position_y - detection.state.position_y), 2);
536
537 const auto p_yaw_rad{mot::remove_units(point.yaw.get_angle())};
538 const auto d_yaw_rad{mot::remove_units(detection.state.yaw.get_angle())};
539 const auto abs_diff{std::abs(p_yaw_rad - d_yaw_rad)};
540 sum += std::min(abs_diff, 2 * 3.14159265359 - abs_diff);
541
542 return sum;
543 }
544
545 template <typename... Alternatives>
546 auto operator()(mot::Point point, const std::variant<Alternatives...> & detection) const -> double
547 {
548 const mot::Visitor visitor{
549 [this](const mot::Point & p, const mot::CtrvDetection & d) { return this->operator()(p, d); },
550 [this](const mot::Point & p, const mot::CtraDetection & d) { return this->operator()(p, d); },
551 [](const mot::Point &, const auto &) {
552 // Currently on support CTRV and CTRA
553 return std::numeric_limits<double>::max();
554 }};
555
556 return std::visit(visitor, std::variant<mot::Point>{point}, detection);
557 }
558};
559
560auto MultipleObjectTrackerNode::execute_pipeline() -> void
561{
562 static constexpr mot::Visitor make_track_visitor{
563 [](const mot::CtrvDetection & d, const mot::Uuid & u) {
564 return Track{mot::make_track<mot::CtrvTrack>(d, u)};
565 },
566 [](const mot::CtraDetection & d, const mot::Uuid & u) {
567 return Track{mot::make_track<mot::CtraTrack>(d, u)};
568 },
569 [](const auto &) {
570 // Currently on support CTRV and CTRA
571 throw std::runtime_error("cannot make track from given detection");
572 },
573 };
574
575 if (track_manager_.get_all_tracks().empty()) {
576 RCLCPP_DEBUG(
577 get_logger(), "List of tracks is empty. Converting detections to tentative tracks");
578
579 // This clustering distance is an arbitrarily-chosen heuristic. It is working well for our
580 // current purposes, but there's no reason it couldn't be restricted or loosened.
581 const auto clusters{mot::cluster_detections(detections_, 0.75)};
582 for (const auto & cluster : clusters) {
583 const auto detection{std::cbegin(cluster.get_detections())->second};
584 const auto uuid_str{mot::get_uuid(detection).value()};
585 // CARLA uses three-digit actor identifiers. We want to UUID scheme to be
586 // <track_number>-<carla_actor_id> for easier visual analysis by users.
587 const mot::Uuid new_uuid{
588 std::to_string(lifetime_generated_track_count_++) +
589 uuid_str.substr(std::size(uuid_str) - 4, 4)};
590 track_manager_.add_tentative_track(
591 std::visit(make_track_visitor, detection, std::variant<mot::Uuid>(new_uuid)));
592 }
593
594 track_list_pub_->publish(carma_cooperative_perception_interfaces::msg::TrackList{});
595
596 detections_.clear();
597 uuid_index_map_.clear();
598 return;
599 }
600
601 const units::time::second_t current_time{this->now().seconds()};
602
603 temporally_align_detections(detections_, current_time);
604
605 const auto predicted_tracks{predict_track_states(track_manager_.get_all_tracks(), current_time)};
606 auto scores{
607 mot::score_tracks_and_detections(predicted_tracks, detections_, SemanticDistance2dScore{})};
608
609 // This pruning distance is an arbitrarily-chosen heuristic. It is working well for our
610 // current purposes, but there's no reason it couldn't be restricted or loosened.
611 mot::prune_track_and_detection_scores_if(scores, [](const auto & score) { return score > 1.0; });
612
613 const auto associations{
614 mot::associate_detections_to_tracks(scores, mot::gnn_association_visitor)};
615
616 track_manager_.update_track_lists(associations);
617
618 std::unordered_map<mot::Uuid, Detection> detection_map;
619 for (const auto & detection : detections_) {
620 detection_map[mot::get_uuid(detection)] = detection;
621 }
622
623 const mot::HasAssociation has_association{associations};
624 for (auto & track : track_manager_.get_all_tracks()) {
625 if (has_association(track)) {
626 const auto detection_uuids{associations.at(get_uuid(track))};
627 const auto first_detection{detection_map[detection_uuids.at(0)]};
628 const auto fused_track{
629 std::visit(mot::covariance_intersection_visitor, track, first_detection)};
630 track_manager_.update_track(mot::get_uuid(track), fused_track);
631 }
632 }
633
634 // Unassociated detections don't influence the tracking pipeline, so we can add
635 // them to the tracker at the end.
636 std::vector<Detection> unassociated_detections;
637 for (const auto & [uuid, detection] : detection_map) {
638 if (!has_association(detection)) {
639 unassociated_detections.push_back(detection);
640 }
641 }
642
643 // We want to remove unassociated tracks that are close enough to existing tracks
644 // to avoid creating duplicates. Duplicate tracks will cause association inconsistencies
645 // (flip flopping associations between the two tracks).
646 auto remove_start{std::remove_if(
647 std::begin(unassociated_detections), std::end(unassociated_detections),
648 [&scores](const auto & detection) {
649 const auto uuid{mot::get_uuid(detection)};
650 auto min_score{std::numeric_limits<float>::infinity()};
651 for (const auto & [uuid_pair, score] : scores) {
652 if (uuid_pair.second == uuid) {
653 min_score = std::min(min_score, score);
654 }
655 }
656
657 // This distance is an arbitrarily-chosen heuristic. It is working well for our
658 // current purposes, but there's no reason it couldn't be restricted or loosened.
659 return min_score < 1.0;
660 })};
661
662 unassociated_detections.erase(remove_start, std::end(unassociated_detections));
663
664 // This clustering distance is an arbitrarily-chosen heuristic. It is working well for our
665 // current purposes, but there's no reason it couldn't be restricted or loosened.
666 const auto clusters{mot::cluster_detections(unassociated_detections, 0.75, MetricSe2{})};
667 for (const auto & cluster : clusters) {
668 const auto detection{std::cbegin(cluster.get_detections())->second};
669 const auto uuid_str{mot::get_uuid(detection).value()};
670 // CARLA uses three-digit actor identifiers. We want to UUID scheme to be
671 // <track_number>-<carla_actor_id> for easier visual analysis by users.
672 const mot::Uuid new_uuid{
673 std::to_string(lifetime_generated_track_count_++) +
674 uuid_str.substr(std::size(uuid_str) - 4, 4)};
675 track_manager_.add_tentative_track(
676 std::visit(make_track_visitor, detection, std::variant<mot::Uuid>(new_uuid)));
677 }
678
679 carma_cooperative_perception_interfaces::msg::TrackList track_list;
680 for (const auto & track : track_manager_.get_confirmed_tracks()) {
681 track_list.tracks.push_back(to_ros_msg(track));
682 }
683
684 track_list_pub_->publish(track_list);
685
686 detections_.clear();
687 uuid_index_map_.clear();
688}
689
690} // namespace carma_cooperative_perception
691
692// This is not our macro, so we should not worry about linting it.
693// clang-tidy added support for ignoring system macros in release 14.0.0 (see the release notes
694// here: https://releases.llvm.org/14.0.0/tools/clang/tools/extra/docs/ReleaseNotes.html), but
695// ament_clang_tidy for ROS 2 Foxy specifically looks for clang-tidy-6.0.
696RCLCPP_COMPONENTS_REGISTER_NODE(carma_cooperative_perception::MultipleObjectTrackerNode) // NOLINT
auto handle_on_configure(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
static auto temporally_align_detections(std::vector< Detection > &detections, units::time::second_t end_time) -> void
auto make_ctra_detection(const carma_cooperative_perception_interfaces::msg::Detection &msg) -> Detection
auto semantic_class_to_numeric_value(mot::SemanticClass semantic_class)
std::variant< multiple_object_tracking::CtrvDetection, multiple_object_tracking::CtraDetection > Detection
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21
static auto predict_track_states(std::vector< Track > tracks, units::time::second_t end_time)
static auto to_ros_msg(const Track &track)
auto make_semantic_class(std::size_t numeric_value)
auto make_ctrv_detection(const carma_cooperative_perception_interfaces::msg::Detection &msg) -> Detection
auto make_detection(const carma_cooperative_perception_interfaces::msg::Detection &msg) -> Detection
constexpr auto remove_units(const T &value)
std::variant< multiple_object_tracking::CtrvTrack, multiple_object_tracking::CtraTrack > Track
static auto to_ros_msg(const mot::CtraTrack &track)
Calculates distance between a point and detection in SE(2) (special Euclidean) space.
auto operator()(const mot::Point &point, const Detection &detection) const -> double
auto operator()(mot::Point point, const std::variant< Alternatives... > &detection) const -> double
Calculate 2D Euclidean distance between track and detection.
static auto two_dimensional_distance(const mot::CtrvState &lhs, const mot::CtrvState &rhs) -> float
auto operator()(const std::variant< TrackAlternatives... > &track, const std::variant< DetectionAlternatives... > &detection) const -> std::optional< float >
auto operator()(const Track &track, const Detection &detection) const -> std::optional< float >
static auto two_dimensional_distance(const mot::CtraState &lhs, const mot::CtraState &rhs) -> float