Class that store externally detected objects with mask. More...
Functions | |
CustomMaskObjectData () | |
Default constructor. More... | |
Attributes | |
String | unique_object_id |
Unique id to help identify and track AI detections. More... | |
std::vector< sl::uint2 > | bounding_box_2d |
2D bounding box of the object represented as four 2D points starting at the top left corner and rotation clockwise. More... | |
int | label |
Object label. More... | |
float | probability |
Detection confidence value of the object. More... | |
bool | is_grounded = true |
Provide hypothesis about the object movements (degrees of freedom or DoF) to improve the object tracking. More... | |
bool | is_static = false |
Provide hypothesis about the object staticity to improve the object tracking. More... | |
float | tracking_timeout = -1.F |
Maximum tracking time threshold (in seconds) before dropping the tracked object when unseen for this amount of time. By default, let the tracker decide internally based on the internal sub class of the tracked object. Only valid for static object. More... | |
float | tracking_max_dist = -1.F |
Maximum tracking distance threshold (in meters) before dropping the tracked object when unseen for this amount of meters. By default, do not discard tracked object based on distance. Only valid for static object. More... | |
sl::Mat | box_mask |
2D mask of the object inside its bounding box. More... | |
Class that store externally detected objects with mask.
The objects can be ingested with sl::Camera.ingestCustomMaskObjects() to extract 3D and tracking information over time.
Default constructor.
String unique_object_id |
Unique id to help identify and track AI detections.
It can be either generated externally, or by using generate_unique_id() or left empty.
std::vector<sl::uint2> bounding_box_2d |
2D bounding box of the object represented as four 2D points starting at the top left corner and rotation clockwise.
[0, 0]
is the top left corner. int label |
Object label.
This information is passed-through and can be used to improve object tracking.
float probability |
Detection confidence value of the object.
[0-1]
. bool is_grounded = true |
Provide hypothesis about the object movements (degrees of freedom or DoF) to improve the object tracking.
bool is_static = false |
Provide hypothesis about the object staticity to improve the object tracking.
float tracking_timeout = -1.F |
Maximum tracking time threshold (in seconds) before dropping the tracked object when unseen for this amount of time. By default, let the tracker decide internally based on the internal sub class of the tracked object. Only valid for static object.
float tracking_max_dist = -1.F |
Maximum tracking distance threshold (in meters) before dropping the tracked object when unseen for this amount of meters. By default, do not discard tracked object based on distance. Only valid for static object.
sl::Mat box_mask |
2D mask of the object inside its bounding box.