DetectedObject.msg 2.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445
  1. std_msgs/Header header
  2. uint32 id
  3. string label
  4. float32 score #Score as defined by the detection, Optional
  5. std_msgs/ColorRGBA color # Define this object specific color
  6. bool valid # Defines if this object is valid, or invalid as defined by the filtering
  7. ################ 3D BB
  8. string space_frame #3D Space coordinate frame of the object, required if pose and dimensions are defines
  9. geometry_msgs/Pose pose
  10. geometry_msgs/Vector3 dimensions
  11. geometry_msgs/Vector3 variance
  12. geometry_msgs/Twist velocity
  13. geometry_msgs/Twist acceleration
  14. sensor_msgs/PointCloud2 pointcloud
  15. geometry_msgs/PolygonStamped convex_hull
  16. LaneArray candidate_trajectories
  17. bool pose_reliable
  18. bool velocity_reliable
  19. bool acceleration_reliable
  20. bool is_static
  21. int32 corner_index
  22. ############### 2D Rect
  23. string image_frame # Image coordinate Frame, Required if x,y,w,h defined
  24. int32 x # X coord in image space(pixel) of the initial point of the Rect
  25. int32 y # Y coord in image space(pixel) of the initial point of the Rect
  26. int32 width # Width of the Rect in pixels
  27. int32 height # Height of the Rect in pixels
  28. float32 angle # Angle [0 to 2*PI), allow rotated rects
  29. sensor_msgs/Image roi_image
  30. ############### Indicator information
  31. uint8 indicator_state # INDICATOR_LEFT = 0, INDICATOR_RIGHT = 1, INDICATOR_BOTH = 2, INDICATOR_NONE = 3
  32. ############### Behavior State of the Detected Object
  33. uint8 behavior_state # FORWARD_STATE = 0, STOPPING_STATE = 1, BRANCH_LEFT_STATE = 2, BRANCH_RIGHT_STATE = 3, YIELDING_STATE = 4, ACCELERATING_STATE = 5, SLOWDOWN_STATE = 6
  34. #
  35. string[] user_defined_info