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.hpp
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
15#ifndef CARMA_COOPERATIVE_PERCEPTION__MULTIPLE_OBJECT_TRACKER_COMPONENT_HPP_
16#define CARMA_COOPERATIVE_PERCEPTION__MULTIPLE_OBJECT_TRACKER_COMPONENT_HPP_
17
18#include <carma_ros2_utils/carma_lifecycle_node.hpp>
19#include <rclcpp/rclcpp.hpp>
20
21#include <carma_cooperative_perception_interfaces/msg/detection_list.hpp>
22#include <carma_cooperative_perception_interfaces/msg/track_list.hpp>
23
24#include <multiple_object_tracking/ctra_model.hpp>
25#include <multiple_object_tracking/ctrv_model.hpp>
26#include <multiple_object_tracking/track_management.hpp>
27#include <unordered_map>
28#include <variant>
29#include <vector>
30
32{
33
34using Detection =
35 std::variant<multiple_object_tracking::CtrvDetection, multiple_object_tracking::CtraDetection>;
36using Track =
37 std::variant<multiple_object_tracking::CtrvTrack, multiple_object_tracking::CtraTrack>;
38
40 -> Detection;
41
42class MultipleObjectTrackerNode : public carma_ros2_utils::CarmaLifecycleNode
43{
44public:
45 explicit MultipleObjectTrackerNode(const rclcpp::NodeOptions & options);
46
47 auto handle_on_configure(const rclcpp_lifecycle::State & /* previous_state */)
48 -> carma_ros2_utils::CallbackReturn override;
49
50 auto handle_on_activate(const rclcpp_lifecycle::State & /* previous_state */)
51 -> carma_ros2_utils::CallbackReturn override;
52
53 auto handle_on_deactivate(const rclcpp_lifecycle::State & /* previous_state */)
54 -> carma_ros2_utils::CallbackReturn override;
55
56 auto handle_on_cleanup(const rclcpp_lifecycle::State & /* previous_state */)
57 -> carma_ros2_utils::CallbackReturn override;
58
59 auto handle_on_shutdown(const rclcpp_lifecycle::State & /* previous_state */)
60 -> carma_ros2_utils::CallbackReturn override;
61
62 auto store_new_detections(const carma_cooperative_perception_interfaces::msg::DetectionList & msg)
63 -> void;
64
65 auto execute_pipeline() -> void;
66
67private:
68 rclcpp::Subscription<carma_cooperative_perception_interfaces::msg::DetectionList>::SharedPtr
70
71 rclcpp_lifecycle::LifecyclePublisher<
72 carma_cooperative_perception_interfaces::msg::TrackList>::SharedPtr track_list_pub_{nullptr};
73
74 rclcpp::TimerBase::SharedPtr pipeline_execution_timer_{nullptr};
75
76 std::vector<Detection> detections_;
77 std::unordered_map<multiple_object_tracking::Uuid, std::size_t> uuid_index_map_;
78 multiple_object_tracking::FixedThresholdTrackManager<Track> track_manager_{
79 multiple_object_tracking::PromotionThreshold{3U},
80 multiple_object_tracking::RemovalThreshold{0U}};
81 units::time::nanosecond_t execution_period_{1 / units::frequency::hertz_t{2.0}};
82 OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_{nullptr};
84};
85
86} // namespace carma_cooperative_perception
87
88#endif // CARMA_COOPERATIVE_PERCEPTION__MULTIPLE_OBJECT_TRACKER_COMPONENT_HPP_
auto handle_on_cleanup(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
auto handle_on_configure(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
rclcpp_lifecycle::LifecyclePublisher< carma_cooperative_perception_interfaces::msg::TrackList >::SharedPtr track_list_pub_
rclcpp::Subscription< carma_cooperative_perception_interfaces::msg::DetectionList >::SharedPtr detection_list_sub_
auto handle_on_activate(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
auto handle_on_deactivate(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
multiple_object_tracking::FixedThresholdTrackManager< Track > track_manager_
auto handle_on_shutdown(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
std::unordered_map< multiple_object_tracking::Uuid, std::size_t > uuid_index_map_
auto store_new_detections(const carma_cooperative_perception_interfaces::msg::DetectionList &msg) -> void
std::variant< multiple_object_tracking::CtrvDetection, multiple_object_tracking::CtraDetection > Detection
auto make_detection(const carma_cooperative_perception_interfaces::msg::Detection &msg) -> Detection
std::variant< multiple_object_tracking::CtrvTrack, multiple_object_tracking::CtraTrack > Track