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.
bounding_box_to_detected_object Namespace Reference

Classes

class  Node
 

Functions

autoware_auto_msgs::msg::DetectedObject detected_obj_from_bounding_box (const autoware_auto_msgs::msg::BoundingBox &box)
 

Function Documentation

◆ detected_obj_from_bounding_box()

autoware_auto_msgs::msg::DetectedObject bounding_box_to_detected_object::detected_obj_from_bounding_box ( const autoware_auto_msgs::msg::BoundingBox &  box)

Definition at line 42 of file bounding_box_to_detected_object_node.cpp.

42 {
43
44 autoware_auto_msgs::msg::DetectedObject obj;
45
46 // The following method currently does not properly set the orientation
47 // so that will be set manually following this call
48 obj = autoware::common::geometry::bounding_box::details::make_detected_object(box);
49
50 obj.kinematics.orientation.x = box.orientation.x;
51 obj.kinematics.orientation.y = box.orientation.y;
52 obj.kinematics.orientation.z = box.orientation.z;
53 obj.kinematics.orientation.w = box.orientation.w;
54 obj.kinematics.orientation_availability = autoware_auto_msgs::msg::DetectedObjectKinematics::SIGN_UNKNOWN;
55
56 return obj;
57
58 }

Referenced by bounding_box_to_detected_object::Node::bbox_callback().

Here is the caller graph for this function: