2525#include < multiple_object_tracking/ctra_model.hpp>
2626#include < multiple_object_tracking/ctrv_model.hpp>
2727#include < multiple_object_tracking/fusing.hpp>
28+ #include < multiple_object_tracking/gating.hpp>
2829#include < multiple_object_tracking/scoring.hpp>
2930#include < multiple_object_tracking/temporal_alignment.hpp>
3031#include < unordered_map>
@@ -232,7 +233,10 @@ static auto to_ros_msg(const Track & track)
232233 static constexpr mot::Visitor visitor{
233234 [](const mot::CtrvTrack & t) { return to_ros_msg (t); },
234235 [](const mot::CtraTrack & t) { return to_ros_msg (t); },
235- [](const auto &) { throw std::runtime_error{" cannot make ROS 2 message from track type" }; }};
236+ [](const auto &) {
237+ // Currently on support CTRV and CTRA
238+ throw std::runtime_error{" cannot make ROS 2 message from track type" };
239+ }};
236240
237241 return std::visit (visitor, track);
238242}
@@ -452,18 +456,123 @@ static auto predict_track_states(std::vector<Track> tracks, units::time::second_
452456 return tracks;
453457}
454458
459+ /* *
460+ * @brief Calculate 2D Euclidean distance between track and detection
461+ *
462+ * If both the track and detection semantic classes are known, this function
463+ * object returns the 2D Euclidean distance between their states. Otherwise,
464+ * it returns std::nullopt.
465+ */
466+ struct SemanticDistance2dScore
467+ {
468+ template <typename Track, typename Detection>
469+ auto operator ()(const Track & track, const Detection & detection) const -> std::optional<float>
470+ {
471+ if constexpr (std::is_same_v<decltype (track.state ), decltype (detection.state )>) {
472+ const auto dist{two_dimensional_distance (track.state , detection.state )};
473+
474+ // Fall back to 2D Euclidean distance if either semantic class if unknown. The unknown
475+ // track/detection may actually be the same other track/detection we are scoring against.
476+ if (
477+ track.semantic_class == mot::SemanticClass::kUnknown ||
478+ detection.semantic_class == mot::SemanticClass::kUnknown ) {
479+ return dist;
480+ }
481+
482+ if (track.semantic_class == detection.semantic_class ) {
483+ return dist;
484+ }
485+ }
486+
487+ return std::nullopt ;
488+ }
489+
490+ template <typename ... TrackAlternatives, typename ... DetectionAlternatives>
491+ auto operator ()(
492+ const std::variant<TrackAlternatives...> & track,
493+ const std::variant<DetectionAlternatives...> & detection) const -> std::optional<float>
494+ {
495+ return std::visit (
496+ [this ](const auto & t, const auto & d) { return (*this )(t, d); }, track, detection);
497+ }
498+
499+ private:
500+ static auto two_dimensional_distance (const mot::CtrvState & lhs, const mot::CtrvState & rhs)
501+ -> float
502+ {
503+ const auto x_diff_sq{
504+ std::pow (mot::remove_units (lhs.position_x ) - mot::remove_units (rhs.position_x ), 2 )};
505+ const auto y_diff_sq{
506+ std::pow (mot::remove_units (lhs.position_y ) - mot::remove_units (rhs.position_y ), 2 )};
507+
508+ return std::sqrt (x_diff_sq + y_diff_sq);
509+ }
510+
511+ static auto two_dimensional_distance (const mot::CtraState & lhs, const mot::CtraState & rhs)
512+ -> float
513+ {
514+ const auto x_diff_sq{
515+ std::pow (mot::remove_units (lhs.position_x ) - mot::remove_units (rhs.position_x ), 2 )};
516+ const auto y_diff_sq{
517+ std::pow (mot::remove_units (lhs.position_y ) - mot::remove_units (rhs.position_y ), 2 )};
518+
519+ return std::sqrt (x_diff_sq + y_diff_sq);
520+ }
521+ };
522+
523+ /* *
524+ * @brief Calculates distance between a point and detection in SE(2) (special Euclidean) space
525+ */
526+ struct MetricSe2
527+ {
528+ template <typename Detection>
529+ auto operator ()(const mot::Point & point, const Detection & detection) const -> double
530+ {
531+ double sum{0 };
532+
533+ sum += std::pow (mot::remove_units (point.position_x - detection.state .position_x ), 2 );
534+ sum += std::pow (mot::remove_units (point.position_y - detection.state .position_y ), 2 );
535+
536+ const auto p_yaw_rad{mot::remove_units (point.yaw .get_angle ())};
537+ const auto d_yaw_rad{mot::remove_units (detection.state .yaw .get_angle ())};
538+ const auto abs_diff{std::abs (p_yaw_rad - d_yaw_rad)};
539+ sum += std::min (abs_diff, 2 * 3.14159265359 - abs_diff);
540+
541+ return sum;
542+ }
543+
544+ template <typename ... Alternatives>
545+ auto operator ()(mot::Point point, const std::variant<Alternatives...> & detection) const -> double
546+ {
547+ const mot::Visitor visitor{
548+ [this ](const mot::Point & p, const mot::CtrvDetection & d) { return this ->operator ()(p, d); },
549+ [this ](const mot::Point & p, const mot::CtraDetection & d) { return this ->operator ()(p, d); },
550+ [](const mot::Point &, const auto &) {
551+ // Currently on support CTRV and CTRA
552+ return std::numeric_limits<double >::max ();
553+ }};
554+
555+ return std::visit (visitor, std::variant<mot::Point>{point}, detection);
556+ }
557+ };
558+
455559auto MultipleObjectTrackerNode::execute_pipeline () -> void
456560{
457561 static constexpr mot::Visitor make_track_visitor{
458562 [](const mot::CtrvDetection & d) { return Track{mot::make_track<mot::CtrvTrack>(d)}; },
459563 [](const mot::CtraDetection & d) { return Track{mot::make_track<mot::CtraTrack>(d)}; },
460- [](const auto &) { throw std::runtime_error (" cannot make track from given detection" ); },
564+ [](const auto &) {
565+ // Currently on support CTRV and CTRA
566+ throw std::runtime_error (" cannot make track from given detection" );
567+ },
461568 };
462569
463570 if (track_manager_.get_all_tracks ().empty ()) {
464571 RCLCPP_DEBUG (
465572 get_logger (), " List of tracks is empty. Converting detections to tentative tracks" );
466573
574+ // This clustering distance is an arbitrarily-chosen heuristic. It is working well for our
575+ // current purposes, but there's no reason it couldn't be restricted or loosened.
467576 const auto clusters{mot::cluster_detections (detections_, 0.75 )};
468577 for (const auto & cluster : clusters) {
469578 const auto detection{std::cbegin (cluster.get_detections ())->second };
@@ -482,10 +591,16 @@ auto MultipleObjectTrackerNode::execute_pipeline() -> void
482591 temporally_align_detections (detections_, current_time);
483592
484593 const auto predicted_tracks{predict_track_states (track_manager_.get_all_tracks (), current_time)};
485- const auto scores{
486- mot::score_tracks_and_detections (predicted_tracks, detections_, mot::euclidean_distance_score)};
594+ auto scores{
595+ mot::score_tracks_and_detections (predicted_tracks, detections_, SemanticDistance2dScore{})};
596+
597+ // This pruning distance is an arbitrarily-chosen heuristic. It is working well for our
598+ // current purposes, but there's no reason it couldn't be restricted or loosened.
599+ mot::prune_track_and_detection_scores_if (scores, [](const auto & score) { return score > 5.0 ; });
600+
601+ const auto associations{
602+ mot::associate_detections_to_tracks (scores, mot::gnn_association_visitor)};
487603
488- const auto associations{mot::associate_detections_to_tracks (scores, mot::gnn_associator)};
489604 track_manager_.update_track_lists (associations);
490605
491606 std::unordered_map<mot::Uuid, Detection> detection_map;
@@ -515,7 +630,9 @@ auto MultipleObjectTrackerNode::execute_pipeline() -> void
515630 }
516631 }
517632
518- const auto clusters{mot::cluster_detections (unassociated_detections, 0.75 )};
633+ // This clustering distance is an arbitrarily-chosen heuristic. It is working well for our
634+ // current purposes, but there's no reason it couldn't be restricted or loosened.
635+ const auto clusters{mot::cluster_detections (unassociated_detections, 0.75 , MetricSe2{})};
519636 for (const auto & cluster : clusters) {
520637 const auto detection{std::cbegin (cluster.get_detections ())->second };
521638 track_manager_.add_tentative_track (std::visit (make_track_visitor, detection));
0 commit comments