15#ifndef CARMA_COOPERATIVE_PERCEPTION__MULTIPLE_OBJECT_TRACKER_COMPONENT_HPP_
16#define CARMA_COOPERATIVE_PERCEPTION__MULTIPLE_OBJECT_TRACKER_COMPONENT_HPP_
18#include <carma_ros2_utils/carma_lifecycle_node.hpp>
19#include <rclcpp/rclcpp.hpp>
21#include <carma_cooperative_perception_interfaces/msg/detection_list.hpp>
22#include <carma_cooperative_perception_interfaces/msg/track_list.hpp>
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>
35 std::variant<multiple_object_tracking::CtrvDetection, multiple_object_tracking::CtraDetection>;
37 std::variant<multiple_object_tracking::CtrvTrack, multiple_object_tracking::CtraTrack>;
48 -> carma_ros2_utils::CallbackReturn
override;
51 -> carma_ros2_utils::CallbackReturn
override;
54 -> carma_ros2_utils::CallbackReturn
override;
57 -> carma_ros2_utils::CallbackReturn
override;
60 -> carma_ros2_utils::CallbackReturn
override;
62 auto store_new_detections(
const carma_cooperative_perception_interfaces::msg::DetectionList & msg)
68 rclcpp::Subscription<carma_cooperative_perception_interfaces::msg::DetectionList>::SharedPtr
71 rclcpp_lifecycle::LifecyclePublisher<
72 carma_cooperative_perception_interfaces::msg::TrackList>::SharedPtr
track_list_pub_{
nullptr};
79 multiple_object_tracking::PromotionThreshold{3U},
80 multiple_object_tracking::RemovalThreshold{0U}};
MultipleObjectTrackerNode(const rclcpp::NodeOptions &options)
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
auto execute_pipeline() -> void
rclcpp_lifecycle::LifecyclePublisher< carma_cooperative_perception_interfaces::msg::TrackList >::SharedPtr track_list_pub_
units::time::nanosecond_t execution_period_
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
std::size_t lifetime_generated_track_count_
rclcpp::TimerBase::SharedPtr pipeline_execution_timer_
auto handle_on_deactivate(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
multiple_object_tracking::FixedThresholdTrackManager< Track > track_manager_
std::vector< Detection > detections_
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
OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_
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