17#ifndef EXTERNAL_OBJECT_WORKER_H
18#define EXTERNAL_OBJECT_WORKER_H
20#include <rclcpp/rclcpp.hpp>
21#include <carma_perception_msgs/msg/external_object.hpp>
22#include <carma_perception_msgs/msg/external_object_list.hpp>
23#include <autoware_auto_msgs/msg/tracked_objects.hpp>
25#include <tf2_ros/transform_listener.h>
26#include <geometry_msgs/msg/transform_stamped.h>
27#include <tf2/convert.h>
28#include <tf2/LinearMath/Transform.h>
29#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
30#include <tf2/LinearMath/Quaternion.h>
31#include <tf2/transform_datatypes.h>
32#include <tf2_ros/transform_listener.h>
33#include <tf2_eigen/tf2_eigen.h>
34#include <boost/optional.hpp>
51 std::function<boost::optional<geometry_msgs::msg::TransformStamped>(
const std::string&,
const std::string&,
const rclcpp::Time& stamp)>;
84 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
logger_;
95 bool isClass(
const autoware_auto_msgs::msg::TrackedObject& obj, uint8_t class_id);
PublishObjectCallback obj_pub_
ObjectDetectionTrackingWorker(PublishObjectCallback obj_pub, TransformLookupCallback tf_lookup, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger)
Constructor.
bool isClass(const autoware_auto_msgs::msg::TrackedObject &obj, uint8_t class_id)
Helper method to check if the provided tracked object has the provided class type.
void detectedObjectCallback(autoware_auto_msgs::msg::TrackedObjects::UniquePtr msg)
detectedObjectCallback populates detected object along with its velocity,yaw, yaw_rate and static/dyn...
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_
void setMapFrame(std::string map_frame)
std::function< void(const carma_perception_msgs::msg::ExternalObjectList &)> PublishObjectCallback
std::function< boost::optional< geometry_msgs::msg::TransformStamped >(const std::string &, const std::string &, const rclcpp::Time &stamp)> TransformLookupCallback
TransformLookupCallback tf_lookup_