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.
object_detection_tracking_worker.h
Go to the documentation of this file.
1/*
2 * Copyright (C) 2019-2021 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#ifndef EXTERNAL_OBJECT_WORKER_H
18#define EXTERNAL_OBJECT_WORKER_H
19
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>
24#include <functional>
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>
35
36namespace object{
37
39{
40
41 public:
42
43 using PublishObjectCallback = std::function<void(const carma_perception_msgs::msg::ExternalObjectList&)>;
44
51 std::function<boost::optional<geometry_msgs::msg::TransformStamped>(const std::string&, const std::string&, const rclcpp::Time& stamp)>;
52
57 ObjectDetectionTrackingWorker(PublishObjectCallback obj_pub, TransformLookupCallback tf_lookup, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger);
58
64 void detectedObjectCallback(autoware_auto_msgs::msg::TrackedObjects::UniquePtr msg);
65
66 // Setters for the parameters
67 void setMapFrame(std::string map_frame);
68
69
70 private:
71
72 // local copy of external object publihsers
73
75
76
77 // local copy of transform lookup callback
79
80 // Parameters
81 std::string map_frame_ = "map";
82
83 // Logger interface
84 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_;
85
86
95 bool isClass(const autoware_auto_msgs::msg::TrackedObject& obj, uint8_t class_id);
96};
97
98}//object
99
100#endif /* EXTERNAL_OBJECT_WORKER_H */
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_
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