|
| 1 | +// Copyright 2024 Tier IV, Inc. |
| 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 | +// |
| 15 | +// |
| 16 | + |
| 17 | +#ifndef MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_ |
| 18 | +#define MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_ |
| 19 | + |
| 20 | +#include "multi_object_tracker/tracker/model/tracker_base.hpp" |
| 21 | + |
| 22 | +#include <rclcpp/rclcpp.hpp> |
| 23 | + |
| 24 | +#include <autoware_perception_msgs/msg/detected_objects.hpp> |
| 25 | +#include <autoware_perception_msgs/msg/tracked_objects.hpp> |
| 26 | + |
| 27 | +#include <list> |
| 28 | +#include <map> |
| 29 | +#include <memory> |
| 30 | +#include <string> |
| 31 | +#include <unordered_map> |
| 32 | +#include <vector> |
| 33 | + |
| 34 | +class TrackerProcessor |
| 35 | +{ |
| 36 | +public: |
| 37 | + explicit TrackerProcessor(const std::map<std::uint8_t, std::string> & tracker_map); |
| 38 | + |
| 39 | + const std::list<std::shared_ptr<Tracker>> & getListTracker() const { return list_tracker_; } |
| 40 | + // tracker processes |
| 41 | + void predict(const rclcpp::Time & time); |
| 42 | + void update( |
| 43 | + const autoware_perception_msgs::msg::DetectedObjects & transformed_objects, |
| 44 | + const geometry_msgs::msg::Transform & self_transform, |
| 45 | + const std::unordered_map<int, int> & direct_assignment); |
| 46 | + void spawn( |
| 47 | + const autoware_perception_msgs::msg::DetectedObjects & detected_objects, |
| 48 | + const geometry_msgs::msg::Transform & self_transform, |
| 49 | + const std::unordered_map<int, int> & reverse_assignment); |
| 50 | + void prune(const rclcpp::Time & time); |
| 51 | + |
| 52 | + // output |
| 53 | + bool isConfidentTracker(const std::shared_ptr<Tracker> & tracker) const; |
| 54 | + void getTrackedObjects( |
| 55 | + const rclcpp::Time & time, |
| 56 | + autoware_perception_msgs::msg::TrackedObjects & tracked_objects) const; |
| 57 | + void getTentativeObjects( |
| 58 | + const rclcpp::Time & time, |
| 59 | + autoware_perception_msgs::msg::TrackedObjects & tentative_objects) const; |
| 60 | + |
| 61 | +private: |
| 62 | + std::map<std::uint8_t, std::string> tracker_map_; |
| 63 | + std::list<std::shared_ptr<Tracker>> list_tracker_; |
| 64 | + |
| 65 | + // parameters |
| 66 | + float max_elapsed_time_; // [s] |
| 67 | + float min_iou_; // [ratio] |
| 68 | + float min_iou_for_unknown_object_; // [ratio] |
| 69 | + double distance_threshold_; // [m] |
| 70 | + int confident_count_threshold_; // [count] |
| 71 | + |
| 72 | + void removeOldTracker(const rclcpp::Time & time); |
| 73 | + void removeOverlappedTracker(const rclcpp::Time & time); |
| 74 | + std::shared_ptr<Tracker> createNewTracker( |
| 75 | + const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, |
| 76 | + const geometry_msgs::msg::Transform & self_transform) const; |
| 77 | +}; |
| 78 | + |
| 79 | +#endif // MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_ |
0 commit comments