robokudo.annotators.static_object_detector¶
Robokudo Static Object Detector Module
This module provides functionality for detecting objects at predefined locations using either manually configured bounding boxes or object knowledge from a database. The detector can create object hypotheses with poses, masks, and class labels.
Note
All poses are defined relative to the camera frame by default unless pose_in_world_coordinates is True.
Classes¶
Generic enumeration. |
|
Find a cluster based on a preconfigured Bounding Box, Pose and Class name. |
Module Contents¶
- class robokudo.annotators.static_object_detector.StaticObjectMode¶
-
Bases:
enum.EnumGeneric enumeration.
Derive from this class to define new enumerations.
- BOUNDING_BOX = 'bounding_box'¶
- OBJECT_KNOWLEDGE_INSTANCE = 'object_knowledge_instance'¶
- OBJECT_KNOWLEDGE_BASE = 'object_knowledge_base'¶
- class robokudo.annotators.static_object_detector.StaticObjectDetectorAnnotator(name='StaticObjectDetector', descriptor=Descriptor())¶
-
Bases:
robokudo.annotators.core.BaseAnnotatorFind a cluster based on a preconfigured Bounding Box, Pose and Class name.
This annotator can:
Create object hypotheses at fixed locations using manual bounding box coordinates
Load object knowledge from a database to automatically infer bounding boxes
Generate pose annotations in either camera or world coordinates
Create masks for the detected regions
Note
The detector supports both Euler angles and quaternions for rotation specification. Parameters can be dynamically reconfigured through ROS dynamic reconfigure.
- class Descriptor¶
-
Bases:
robokudo.annotators.core.BaseAnnotator.DescriptorConfiguration descriptor for the StaticObjectDetectorAnnotator.
Defines all configurable parameters including:
Bounding box dimensions and position
Object knowledge database settings
Pose generation options
Coordinate frame settings
- class Parameters¶
-
Parameters controlling the static object detection behavior.
- bounding_box_x = 1¶
- bounding_box_y = 1¶
- bounding_box_width = 10¶
- bounding_box_height = 10¶
- mode¶
- class_name = 'unknown'¶
- class_names = []¶
- create_pose_annotation = False¶
- create_bounding_box_annotation = False¶
- create_mask = True¶
- object_knowledge_base_ros_package = 'robokudo'¶
- object_knowledge_base_name = 'object_knowledge_iai_kitchen'¶
- object_knowledge_instance: robokudo.object_knowledge_base.ObjectKnowledge | None = None¶
- parameters¶
- color = None¶
- depth = None¶
- cloud = None¶
- cam_intrinsics = None¶
- object_kb = None¶
- object_knowledge = None¶
- detect_from_bb_descriptor(color_rgb: numpy.ndarray) robokudo.types.scene.ObjectHypothesis¶
-
Detect only based on the BB.
- Parameters:
-
color_rgb (np.ndarray) – Image in RGB order
- Returns:
-
robokudo.types.scene.ObjectHypothesis
- detect_from_object_knowledge(object_knowledge: robokudo.object_knowledge_base.ObjectKnowledge, object_id: int = 0) robokudo.types.scene.ObjectHypothesis | None¶
-
Detect from singular, passed ObjectKnowledge instance
- Returns:
-
robokudo.types.scene.ObjectHypothesis
- detect_from_object_knowledge_base() list[robokudo.types.scene.ObjectHypothesis]¶
-
Detect from a completed object knowledge base
- Returns:
-
robokudo.types.scene.ObjectHypothesis
- update()¶
-
Process current scene to detect configured static objects.
Steps:
Gets current color image, depth image and point cloud
If using object knowledge, validates object class exists
Scales color image to match depth image
-
Creates object hypothesis with:
Bounding box from configuration or object knowledge
Pose annotation if enabled
Point cloud from ROI
Mask if enabled
- Returns:
-
SUCCESS if detection completed, FAILURE if required transforms not found
- Return type:
-
py_trees.common.Status
- Raises:
-
Exception – If camera parameters are invalid or missing
- static add_classification_annotation(object_hypothesis: robokudo.types.scene.ObjectHypothesis, class_name: str)¶
- get_rotation_list_based_on_parameters(rotation_x: float, rotation_y: float, rotation_z: float, rotation_w: float) list¶
-
Return a quaternion based on the parametrization of the Annotator.
- Parameters:
-
rotation_x –
rotation_y –
rotation_z –
rotation_w –
- Returns:
-
4-dim list with Quaternion
- get_cloud_from_2d_bb_roi(color_rgb)¶