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.
|
#include <object_detection_tracking_node.h>
Public Member Functions | |
ObjectDetectionTrackingNode (const rclcpp::NodeOptions &) | |
ObjectDetectionTrackingNode constructor. More... | |
void | publishObject (const carma_perception_msgs::msg::ExternalObjectList &obj_msg) |
Callback to publish ObjectList. More... | |
boost::optional< geometry_msgs::msg::TransformStamped > | lookupTransform (const std::string &parent, const std::string &child, const rclcpp::Time &stamp) |
Callback to lookup a transform between two frames. More... | |
carma_ros2_utils::CallbackReturn | handle_on_configure (const rclcpp_lifecycle::State &) |
Private Attributes | |
carma_ros2_utils::SubPtr< autoware_auto_msgs::msg::TrackedObjects > | autoware_obj_sub_ |
carma_ros2_utils::PubPtr< carma_perception_msgs::msg::ExternalObjectList > | carma_obj_pub_ |
ObjectDetectionTrackingWorker | object_worker_ |
std::shared_ptr< tf2_ros::Buffer > | tfBuffer_ |
std::shared_ptr< tf2_ros::TransformListener > | tfListener_ |
std::string | map_frame_ |
Definition at line 31 of file object_detection_tracking_node.h.
|
explicit |
ObjectDetectionTrackingNode constructor.
Definition at line 24 of file object_detection_tracking_node.cpp.
References map_frame_, tfBuffer_, and tfListener_.
carma_ros2_utils::CallbackReturn object::ObjectDetectionTrackingNode::handle_on_configure | ( | const rclcpp_lifecycle::State & | ) |
Definition at line 39 of file object_detection_tracking_node.cpp.
References autoware_obj_sub_, carma_obj_pub_, object::ObjectDetectionTrackingWorker::detectedObjectCallback(), map_frame_, object_worker_, and object::ObjectDetectionTrackingWorker::setMapFrame().
boost::optional< geometry_msgs::msg::TransformStamped > object::ObjectDetectionTrackingNode::lookupTransform | ( | const std::string & | parent, |
const std::string & | child, | ||
const rclcpp::Time & | stamp | ||
) |
Callback to lookup a transform between two frames.
parent | The parent frame |
child | The child frame |
stamp | The time stamp of the transform |
Definition at line 81 of file object_detection_tracking_node.cpp.
References tfBuffer_.
void object::ObjectDetectionTrackingNode::publishObject | ( | const carma_perception_msgs::msg::ExternalObjectList & | obj_msg | ) |
Callback to publish ObjectList.
Definition at line 75 of file object_detection_tracking_node.cpp.
References carma_obj_pub_.
|
private |
Definition at line 37 of file object_detection_tracking_node.h.
Referenced by handle_on_configure().
|
private |
Definition at line 40 of file object_detection_tracking_node.h.
Referenced by handle_on_configure(), and publishObject().
|
private |
Definition at line 52 of file object_detection_tracking_node.h.
Referenced by ObjectDetectionTrackingNode(), and handle_on_configure().
|
private |
Definition at line 43 of file object_detection_tracking_node.h.
Referenced by handle_on_configure().
|
private |
Definition at line 46 of file object_detection_tracking_node.h.
Referenced by ObjectDetectionTrackingNode(), and lookupTransform().
|
private |
Definition at line 49 of file object_detection_tracking_node.h.
Referenced by ObjectDetectionTrackingNode().