5.3. Database API

5.3.1. Database modules

Implementation of the Database modules.

pydantic model voraus_roboception_app.modules.database_modules.DeleteRegionsOfInterest2DRequest

Bases: BaseModel

The request arguments of a delete_regions_of_interest_2d service request of the RoiDB module.

Show JSON schema
{
   "title": "DeleteRegionsOfInterest2DRequest",
   "description": "The request arguments of a delete_regions_of_interest_2d service request of the RoiDB module.",
   "type": "object",
   "properties": {
      "region_of_interest_2d_ids": {
         "items": {
            "type": "string"
         },
         "title": "Region Of Interest 2D Ids",
         "type": "array"
      }
   },
   "required": [
      "region_of_interest_2d_ids"
   ]
}

Fields:
field region_of_interest_2d_ids: List[str] [Required]
pydantic model voraus_roboception_app.modules.database_modules.DeleteRegionsOfInterestRequest

Bases: BaseModel

The request arguments of a delete_regions_of_interest service request of the RoiDB module.

Show JSON schema
{
   "title": "DeleteRegionsOfInterestRequest",
   "description": "The request arguments of a delete_regions_of_interest service request of the RoiDB module.",
   "type": "object",
   "properties": {
      "region_of_interest_ids": {
         "items": {
            "type": "string"
         },
         "title": "Region Of Interest Ids",
         "type": "array"
      }
   },
   "required": [
      "region_of_interest_ids"
   ]
}

Fields:
field region_of_interest_ids: List[str] [Required]
pydantic model voraus_roboception_app.modules.database_modules.GetGrippersRequest

Bases: BaseModel

The request arguments of a get regions of interest service request of the RoiDB module.

Show JSON schema
{
   "title": "GetGrippersRequest",
   "description": "The request arguments of a get regions of interest service request of the RoiDB module.",
   "type": "object",
   "properties": {
      "gripper_ids": {
         "anyOf": [
            {
               "items": {
                  "type": "string"
               },
               "type": "array"
            },
            {
               "type": "null"
            }
         ],
         "default": null,
         "title": "Gripper Ids"
      }
   }
}

Fields:
field gripper_ids: Optional[List[str]] = None
pydantic model voraus_roboception_app.modules.database_modules.GetGrippersResult

Bases: ServiceResponse

Results of the get regions of interest service request of the RoiDB module.

Show JSON schema
{
   "title": "GetGrippersResult",
   "description": "Results of the get regions of interest service request of the RoiDB module.",
   "type": "object",
   "properties": {
      "return_code": {
         "$ref": "#/$defs/ReturnCodeModel"
      },
      "grippers": {
         "items": {
            "$ref": "#/$defs/GrippersModel"
         },
         "title": "Grippers",
         "type": "array"
      }
   },
   "$defs": {
      "CylinderModel": {
         "description": "Description model of a Cylinder.",
         "properties": {
            "radius": {
               "title": "Radius",
               "type": "number"
            },
            "height": {
               "title": "Height",
               "type": "number"
            }
         },
         "required": [
            "radius",
            "height"
         ],
         "title": "CylinderModel",
         "type": "object"
      },
      "ElementsModel": {
         "description": "Part of the GrippersModel.",
         "properties": {
            "parent_id": {
               "title": "Parent Id",
               "type": "string"
            },
            "id": {
               "title": "Id",
               "type": "string"
            },
            "pose": {
               "$ref": "#/$defs/PoseModel"
            },
            "type": {
               "title": "Type",
               "type": "string"
            },
            "box": {
               "$ref": "#/$defs/PosePositionModel"
            },
            "cylinder": {
               "$ref": "#/$defs/CylinderModel"
            }
         },
         "required": [
            "parent_id",
            "id",
            "pose",
            "type",
            "box",
            "cylinder"
         ],
         "title": "ElementsModel",
         "type": "object"
      },
      "GrippersModel": {
         "description": "Result of a get grippers service request of the GripperDB module.",
         "properties": {
            "id": {
               "title": "Id",
               "type": "string"
            },
            "flange_radius": {
               "title": "Flange Radius",
               "type": "number"
            },
            "type": {
               "title": "Type",
               "type": "string"
            },
            "tcp_pose_parent": {
               "$ref": "#/$defs/PoseModel"
            },
            "tcp_parent_id": {
               "title": "Tcp Parent Id",
               "type": "string"
            },
            "elements": {
               "items": {
                  "$ref": "#/$defs/ElementsModel"
               },
               "title": "Elements",
               "type": "array"
            },
            "tcp_pose_flange": {
               "$ref": "#/$defs/PoseModel"
            }
         },
         "required": [
            "id",
            "flange_radius",
            "type",
            "tcp_pose_parent",
            "tcp_parent_id",
            "elements",
            "tcp_pose_flange"
         ],
         "title": "GrippersModel",
         "type": "object"
      },
      "PoseModel": {
         "description": "Pose definition using quaternion for rotation representation.",
         "properties": {
            "position": {
               "$ref": "#/$defs/PosePositionModel"
            },
            "orientation": {
               "$ref": "#/$defs/PoseOrientationModel"
            }
         },
         "required": [
            "position",
            "orientation"
         ],
         "title": "PoseModel",
         "type": "object"
      },
      "PoseOrientationModel": {
         "description": "Orientation as quaternion.",
         "properties": {
            "x": {
               "title": "X",
               "type": "number"
            },
            "y": {
               "title": "Y",
               "type": "number"
            },
            "z": {
               "title": "Z",
               "type": "number"
            },
            "w": {
               "title": "W",
               "type": "number"
            }
         },
         "required": [
            "x",
            "y",
            "z",
            "w"
         ],
         "title": "PoseOrientationModel",
         "type": "object"
      },
      "PosePositionModel": {
         "description": "3D cartesian position.",
         "properties": {
            "x": {
               "title": "X",
               "type": "number"
            },
            "y": {
               "title": "Y",
               "type": "number"
            },
            "z": {
               "title": "Z",
               "type": "number"
            }
         },
         "required": [
            "x",
            "y",
            "z"
         ],
         "title": "PosePositionModel",
         "type": "object"
      },
      "ReturnCodeModel": {
         "description": "A unified return code that is shared along all types of requests.\n\nDifferent styles of return code and message formats exist in the API. They are all converted to this common model.\n\nAlways use the success flag to evaluate whether the request was successful or not.\nDepending on the request, a positive value might represent a successful or erroneous response.",
         "properties": {
            "value": {
               "title": "Value",
               "type": "integer"
            },
            "message": {
               "title": "Message",
               "type": "string"
            },
            "success": {
               "title": "Success",
               "type": "boolean"
            }
         },
         "required": [
            "value",
            "message",
            "success"
         ],
         "title": "ReturnCodeModel",
         "type": "object"
      }
   },
   "required": [
      "return_code",
      "grippers"
   ]
}

Fields:
Validators:

field grippers: List[GrippersModel] [Required]
Validated by:
pydantic model voraus_roboception_app.modules.database_modules.GetLoadCarriersRequest

Bases: BaseModel

The request arguments of a get load carriers service request of the LoadCarrierDB module.

Show JSON schema
{
   "title": "GetLoadCarriersRequest",
   "description": "The request arguments of a get load carriers service request of the LoadCarrierDB module.",
   "type": "object",
   "properties": {
      "load_carrier_ids": {
         "anyOf": [
            {
               "items": {
                  "type": "string"
               },
               "type": "array"
            },
            {
               "type": "null"
            }
         ],
         "default": null,
         "title": "Load Carrier Ids"
      }
   }
}

Fields:
field load_carrier_ids: Optional[List[str]] = None
pydantic model voraus_roboception_app.modules.database_modules.GetLoadCarriersResult

Bases: ServiceResponse

Results of the get load carriers service request of the LoadCarrierDB module.

Show JSON schema
{
   "title": "GetLoadCarriersResult",
   "description": "Results of the get load carriers service request of the LoadCarrierDB module.",
   "type": "object",
   "properties": {
      "return_code": {
         "$ref": "#/$defs/ReturnCodeModel"
      },
      "load_carriers": {
         "items": {
            "$ref": "#/$defs/LoadCarrierModel"
         },
         "title": "Load Carriers",
         "type": "array"
      }
   },
   "$defs": {
      "LoadCarrierModel": {
         "description": "Load carrier definition.\n\nPydantic model is incomplete, some of the parameters depend on each other, but this hierarchy is not implemented\nyet.",
         "properties": {
            "id": {
               "title": "Id",
               "type": "string"
            },
            "type": {
               "title": "Type",
               "type": "string"
            },
            "outer_dimensions": {
               "$ref": "#/$defs/PosePositionModel"
            },
            "inner_dimensions": {
               "$ref": "#/$defs/PosePositionModel"
            },
            "rim_thickness": {
               "anyOf": [
                  {
                     "$ref": "#/$defs/Position2DModel"
                  },
                  {
                     "type": "null"
                  }
               ],
               "default": null
            },
            "rim_step_height": {
               "anyOf": [
                  {
                     "type": "number"
                  },
                  {
                     "type": "null"
                  }
               ],
               "default": null,
               "title": "Rim Step Height"
            },
            "rim_ledge": {
               "anyOf": [
                  {
                     "$ref": "#/$defs/Position2DModel"
                  },
                  {
                     "type": "null"
                  }
               ],
               "default": null
            },
            "height_open_side": {
               "anyOf": [
                  {
                     "type": "number"
                  },
                  {
                     "type": "null"
                  }
               ],
               "default": null,
               "title": "Height Open Side"
            },
            "pose_frame": {
               "title": "Pose Frame",
               "type": "string"
            },
            "pose": {
               "$ref": "#/$defs/PoseModel"
            },
            "overfilled": {
               "anyOf": [
                  {
                     "type": "boolean"
                  },
                  {
                     "type": "null"
                  }
               ],
               "default": null,
               "title": "Overfilled"
            }
         },
         "required": [
            "id",
            "type",
            "outer_dimensions",
            "inner_dimensions",
            "pose_frame",
            "pose"
         ],
         "title": "LoadCarrierModel",
         "type": "object"
      },
      "PoseModel": {
         "description": "Pose definition using quaternion for rotation representation.",
         "properties": {
            "position": {
               "$ref": "#/$defs/PosePositionModel"
            },
            "orientation": {
               "$ref": "#/$defs/PoseOrientationModel"
            }
         },
         "required": [
            "position",
            "orientation"
         ],
         "title": "PoseModel",
         "type": "object"
      },
      "PoseOrientationModel": {
         "description": "Orientation as quaternion.",
         "properties": {
            "x": {
               "title": "X",
               "type": "number"
            },
            "y": {
               "title": "Y",
               "type": "number"
            },
            "z": {
               "title": "Z",
               "type": "number"
            },
            "w": {
               "title": "W",
               "type": "number"
            }
         },
         "required": [
            "x",
            "y",
            "z",
            "w"
         ],
         "title": "PoseOrientationModel",
         "type": "object"
      },
      "PosePositionModel": {
         "description": "3D cartesian position.",
         "properties": {
            "x": {
               "title": "X",
               "type": "number"
            },
            "y": {
               "title": "Y",
               "type": "number"
            },
            "z": {
               "title": "Z",
               "type": "number"
            }
         },
         "required": [
            "x",
            "y",
            "z"
         ],
         "title": "PosePositionModel",
         "type": "object"
      },
      "Position2DModel": {
         "description": "2D cartesian position.",
         "properties": {
            "x": {
               "title": "X",
               "type": "number"
            },
            "y": {
               "title": "Y",
               "type": "number"
            }
         },
         "required": [
            "x",
            "y"
         ],
         "title": "Position2DModel",
         "type": "object"
      },
      "ReturnCodeModel": {
         "description": "A unified return code that is shared along all types of requests.\n\nDifferent styles of return code and message formats exist in the API. They are all converted to this common model.\n\nAlways use the success flag to evaluate whether the request was successful or not.\nDepending on the request, a positive value might represent a successful or erroneous response.",
         "properties": {
            "value": {
               "title": "Value",
               "type": "integer"
            },
            "message": {
               "title": "Message",
               "type": "string"
            },
            "success": {
               "title": "Success",
               "type": "boolean"
            }
         },
         "required": [
            "value",
            "message",
            "success"
         ],
         "title": "ReturnCodeModel",
         "type": "object"
      }
   },
   "required": [
      "return_code",
      "load_carriers"
   ]
}

Fields:
Validators:

field load_carriers: List[LoadCarrierModel] [Required]
Validated by:
pydantic model voraus_roboception_app.modules.database_modules.GetRegionsOfInterest2DRequest

Bases: BaseModel

The request arguments of a get_regions_of_interest_2d service request of the RoiDB module.

Show JSON schema
{
   "title": "GetRegionsOfInterest2DRequest",
   "description": "The request arguments of a get_regions_of_interest_2d service request of the RoiDB module.",
   "type": "object",
   "properties": {
      "region_of_interest_2d_ids": {
         "anyOf": [
            {
               "items": {
                  "type": "string"
               },
               "type": "array"
            },
            {
               "type": "null"
            }
         ],
         "default": null,
         "title": "Region Of Interest 2D Ids"
      }
   }
}

Fields:
field region_of_interest_2d_ids: Optional[List[str]] = None
pydantic model voraus_roboception_app.modules.database_modules.GetRegionsOfInterest2DResult

Bases: ServiceResponse

Results of the get 2d get_regions_of_interest_2d service request of the RoiDB module.

Show JSON schema
{
   "title": "GetRegionsOfInterest2DResult",
   "description": "Results of the get 2d get_regions_of_interest_2d service request of the RoiDB module.",
   "type": "object",
   "properties": {
      "return_code": {
         "$ref": "#/$defs/ReturnCodeModel"
      },
      "regions_of_interest": {
         "items": {
            "$ref": "#/$defs/RegionsOfInterest2DModel"
         },
         "title": "Regions Of Interest",
         "type": "array"
      }
   },
   "$defs": {
      "RegionsOfInterest2DModel": {
         "description": "Result of a get 2d regions of interest service request by the RoiDB module.",
         "properties": {
            "id": {
               "title": "Id",
               "type": "string"
            },
            "offset_x": {
               "title": "Offset X",
               "type": "integer"
            },
            "offset_y": {
               "title": "Offset Y",
               "type": "integer"
            },
            "width": {
               "title": "Width",
               "type": "integer"
            },
            "height": {
               "title": "Height",
               "type": "integer"
            }
         },
         "required": [
            "id",
            "offset_x",
            "offset_y",
            "width",
            "height"
         ],
         "title": "RegionsOfInterest2DModel",
         "type": "object"
      },
      "ReturnCodeModel": {
         "description": "A unified return code that is shared along all types of requests.\n\nDifferent styles of return code and message formats exist in the API. They are all converted to this common model.\n\nAlways use the success flag to evaluate whether the request was successful or not.\nDepending on the request, a positive value might represent a successful or erroneous response.",
         "properties": {
            "value": {
               "title": "Value",
               "type": "integer"
            },
            "message": {
               "title": "Message",
               "type": "string"
            },
            "success": {
               "title": "Success",
               "type": "boolean"
            }
         },
         "required": [
            "value",
            "message",
            "success"
         ],
         "title": "ReturnCodeModel",
         "type": "object"
      }
   },
   "required": [
      "return_code",
      "regions_of_interest"
   ]
}

Fields:
Validators:

field regions_of_interest: List[RegionsOfInterest2DModel] [Required]
Validated by:
pydantic model voraus_roboception_app.modules.database_modules.GetRegionsOfInterestRequest

Bases: BaseModel

The request arguments of a get_regions_of_interest service request of the RoiDB module.

Show JSON schema
{
   "title": "GetRegionsOfInterestRequest",
   "description": "The request arguments of a get_regions_of_interest service request of the RoiDB module.",
   "type": "object",
   "properties": {
      "region_of_interest_ids": {
         "anyOf": [
            {
               "items": {
                  "type": "string"
               },
               "type": "array"
            },
            {
               "type": "null"
            }
         ],
         "default": null,
         "title": "Region Of Interest Ids"
      }
   }
}

Fields:
field region_of_interest_ids: Optional[List[str]] = None
pydantic model voraus_roboception_app.modules.database_modules.GetRegionsOfInterestResult

Bases: ServiceResponse

Results of the get_regions_of_interest service request of the RoiDB module.

Show JSON schema
{
   "title": "GetRegionsOfInterestResult",
   "description": "Results of the get_regions_of_interest service request of the RoiDB module.",
   "type": "object",
   "properties": {
      "return_code": {
         "$ref": "#/$defs/ReturnCodeModel"
      },
      "regions_of_interest": {
         "items": {
            "$ref": "#/$defs/RegionsOfInterestModel"
         },
         "title": "Regions Of Interest",
         "type": "array"
      }
   },
   "$defs": {
      "PoseModel": {
         "description": "Pose definition using quaternion for rotation representation.",
         "properties": {
            "position": {
               "$ref": "#/$defs/PosePositionModel"
            },
            "orientation": {
               "$ref": "#/$defs/PoseOrientationModel"
            }
         },
         "required": [
            "position",
            "orientation"
         ],
         "title": "PoseModel",
         "type": "object"
      },
      "PoseOrientationModel": {
         "description": "Orientation as quaternion.",
         "properties": {
            "x": {
               "title": "X",
               "type": "number"
            },
            "y": {
               "title": "Y",
               "type": "number"
            },
            "z": {
               "title": "Z",
               "type": "number"
            },
            "w": {
               "title": "W",
               "type": "number"
            }
         },
         "required": [
            "x",
            "y",
            "z",
            "w"
         ],
         "title": "PoseOrientationModel",
         "type": "object"
      },
      "PosePositionModel": {
         "description": "3D cartesian position.",
         "properties": {
            "x": {
               "title": "X",
               "type": "number"
            },
            "y": {
               "title": "Y",
               "type": "number"
            },
            "z": {
               "title": "Z",
               "type": "number"
            }
         },
         "required": [
            "x",
            "y",
            "z"
         ],
         "title": "PosePositionModel",
         "type": "object"
      },
      "RegionsOfInterestModel": {
         "description": "Result of a get regions of interest service request by the RoiDB module.\n\nThe values of box/sphere are only valid if the designated type was requested by type_value.\nThe values of the non-requested type default to zero.",
         "properties": {
            "id": {
               "title": "Id",
               "type": "string"
            },
            "type": {
               "enum": [
                  "BOX",
                  "SPHERE"
               ],
               "title": "Type",
               "type": "string"
            },
            "pose_frame": {
               "title": "Pose Frame",
               "type": "string"
            },
            "pose": {
               "$ref": "#/$defs/PoseModel"
            },
            "box": {
               "anyOf": [
                  {
                     "$ref": "#/$defs/PosePositionModel"
                  },
                  {
                     "type": "null"
                  }
               ],
               "default": null
            },
            "sphere": {
               "anyOf": [
                  {
                     "$ref": "#/$defs/SphereModel"
                  },
                  {
                     "type": "null"
                  }
               ],
               "default": null
            }
         },
         "required": [
            "id",
            "type",
            "pose_frame",
            "pose"
         ],
         "title": "RegionsOfInterestModel",
         "type": "object"
      },
      "ReturnCodeModel": {
         "description": "A unified return code that is shared along all types of requests.\n\nDifferent styles of return code and message formats exist in the API. They are all converted to this common model.\n\nAlways use the success flag to evaluate whether the request was successful or not.\nDepending on the request, a positive value might represent a successful or erroneous response.",
         "properties": {
            "value": {
               "title": "Value",
               "type": "integer"
            },
            "message": {
               "title": "Message",
               "type": "string"
            },
            "success": {
               "title": "Success",
               "type": "boolean"
            }
         },
         "required": [
            "value",
            "message",
            "success"
         ],
         "title": "ReturnCodeModel",
         "type": "object"
      },
      "SphereModel": {
         "description": "Used inside the RegionsOfInterestModel.",
         "properties": {
            "radius": {
               "title": "Radius",
               "type": "number"
            }
         },
         "required": [
            "radius"
         ],
         "title": "SphereModel",
         "type": "object"
      }
   },
   "required": [
      "return_code",
      "regions_of_interest"
   ]
}

Fields:
Validators:

field regions_of_interest: List[RegionsOfInterestModel] [Required]
Validated by:
class voraus_roboception_app.modules.database_modules.GripperDB(client)

Bases: object

The gripper data base class. Official API documentation: https://doc.rc-cube.com/latest/en/gripper_db.html.

get_grippers(gripper_ids=None)

Send a service request to the roboception to retrieve the stored gripper ids.

Parameters:

gripper_ids (Optional[List[str]], optional) – Used to filter the results. Defaults to None.

Returns:

Result of the service request

Return type:

GetGrippersResult

node_name: str = 'rc_gripper_db'
class voraus_roboception_app.modules.database_modules.LoadCarrierDB(client)

Bases: object

The load carrier data base class.

Official API documentation: https://doc.rc-cube.com/latest/en/loadcarrier_db.html.

get_load_carriers(load_carrier_ids=None)

Send a service request to the roboception to retrieve the stored load carriers.

Parameters:

load_carrier_ids (Optional[List[str]], optional) – Used to filter the results. Defaults to None.

Returns:

Result of the service request

Return type:

GetLoadCarriersResult

node_name: str = 'rc_load_carrier_db'
class voraus_roboception_app.modules.database_modules.RoiDB(client)

Bases: object

The region of interest data base class.

Official API documentation: https://doc.rc-cube.com/latest/en/roi.html.

delete_regions_of_interest(region_of_interest_ids)

Deletes the configured 3D regions of interest with the requested region_of_interest_ids.

All regions of interest to be deleted must be explicitly stated in region_of_interest_ids

Parameters:

region_of_interest_ids (List[str]) – List of the 3D regions of in interest to be deleted

Return type:

ServiceResponse

Returns:

Service response

delete_regions_of_interest_2d(region_of_interest_2d_ids)

Deletes the configured 2D regions of interest with the requested region_of_interest_2d_ids.

All regions of interest to be deleted must be explicitly stated in region_of_interest_2d_ids

Parameters:

region_of_interest_2d_ids (List[str]) – List of the 2D regions of in interest to be deleted

Return type:

ServiceResponse

Returns:

Service response

get_regions_of_interest(region_of_interest_ids=None)

Send a service request to the roboception to retrieve the stored regions of interest.

Parameters:

region_of_interest_ids (Optional[List[str]], optional) – Used to filter the results. Defaults to None.

Returns:

Result of the service request

Return type:

GetRegionsOfInterestResult

get_regions_of_interest_2d(region_of_interest_2d_ids=None)

Send a service request to the roboception to retrieve the stored 2d regions of interest.

Parameters:

region_of_interest_2d_ids (Optional[List[str]], optional) – Used to filter the results. Defaults to None.

Returns:

Result of the service request

Return type:

GetRegionsOfInterestResult

node_name: str = 'rc_roi_db'
set_region_of_interest(id_value, type_value, pose, box=None, sphere=None, pose_frame='camera')

Send a service request to the roboception to create a 3d region of interest.

Parameters:
  • id_value (str) – Name of the ROI

  • type_value (Literal['BOX', 'SPHERE']) – Either Sphere or Box

  • pose (PoseModel) – Pose of the ROI in Roboception’s Roll/Pitch/Yaw notation

  • box (Optional[PosePositionModel]) – Roboceptions ‘Box’ description containing x, y and z dimensions of the ROI in [m].

  • sphere (Optional[SphereModel]) – Roboceptions ‘Sphere’ description containing the radius in [m].

  • pose_frame (str) – Reference frame in which the poses will be returned, either “camera” or “external”. Defaults to “camera”.

Return type:

ServiceResponse

Returns:

Service response.

set_region_of_interest_2d(id_value, height, width, offset_x, offset_y)

Send a service request to the roboception to create a 2d region of interest.

Parameters:
  • id_value (str) – Unique name of the region of interest

  • height (int) – height in pixels

  • width (int) – width in pixels

  • offset_x (int) – offset in pixels along the x-axis from the top-left corner of the image

  • offset_y (int) – offset in pixels along the y-axis from the top-left corner of the image

Return type:

ServiceResponse

Returns:

Service response

pydantic model voraus_roboception_app.modules.database_modules.SetRegionOfInterest2DRequest

Bases: BaseModel

The request arguments of a set_region_of_interest_2d service request of the RoiDB module.

Show JSON schema
{
   "title": "SetRegionOfInterest2DRequest",
   "description": "The request arguments of a set_region_of_interest_2d service request of the RoiDB module.",
   "type": "object",
   "properties": {
      "region_of_interest_2d": {
         "$ref": "#/$defs/RegionsOfInterest2DModel"
      }
   },
   "$defs": {
      "RegionsOfInterest2DModel": {
         "description": "Result of a get 2d regions of interest service request by the RoiDB module.",
         "properties": {
            "id": {
               "title": "Id",
               "type": "string"
            },
            "offset_x": {
               "title": "Offset X",
               "type": "integer"
            },
            "offset_y": {
               "title": "Offset Y",
               "type": "integer"
            },
            "width": {
               "title": "Width",
               "type": "integer"
            },
            "height": {
               "title": "Height",
               "type": "integer"
            }
         },
         "required": [
            "id",
            "offset_x",
            "offset_y",
            "width",
            "height"
         ],
         "title": "RegionsOfInterest2DModel",
         "type": "object"
      }
   },
   "required": [
      "region_of_interest_2d"
   ]
}

Fields:
field region_of_interest_2d: RegionsOfInterest2DModel [Required]
pydantic model voraus_roboception_app.modules.database_modules.SetRegionOfInterestRequest

Bases: BaseModel

The request arguments of a set_region_of_interest service request of the RoiDB module.

Show JSON schema
{
   "title": "SetRegionOfInterestRequest",
   "description": "The request arguments of a set_region_of_interest service request of the RoiDB module.",
   "type": "object",
   "properties": {
      "region_of_interest": {
         "$ref": "#/$defs/RegionsOfInterestModel"
      }
   },
   "$defs": {
      "PoseModel": {
         "description": "Pose definition using quaternion for rotation representation.",
         "properties": {
            "position": {
               "$ref": "#/$defs/PosePositionModel"
            },
            "orientation": {
               "$ref": "#/$defs/PoseOrientationModel"
            }
         },
         "required": [
            "position",
            "orientation"
         ],
         "title": "PoseModel",
         "type": "object"
      },
      "PoseOrientationModel": {
         "description": "Orientation as quaternion.",
         "properties": {
            "x": {
               "title": "X",
               "type": "number"
            },
            "y": {
               "title": "Y",
               "type": "number"
            },
            "z": {
               "title": "Z",
               "type": "number"
            },
            "w": {
               "title": "W",
               "type": "number"
            }
         },
         "required": [
            "x",
            "y",
            "z",
            "w"
         ],
         "title": "PoseOrientationModel",
         "type": "object"
      },
      "PosePositionModel": {
         "description": "3D cartesian position.",
         "properties": {
            "x": {
               "title": "X",
               "type": "number"
            },
            "y": {
               "title": "Y",
               "type": "number"
            },
            "z": {
               "title": "Z",
               "type": "number"
            }
         },
         "required": [
            "x",
            "y",
            "z"
         ],
         "title": "PosePositionModel",
         "type": "object"
      },
      "RegionsOfInterestModel": {
         "description": "Result of a get regions of interest service request by the RoiDB module.\n\nThe values of box/sphere are only valid if the designated type was requested by type_value.\nThe values of the non-requested type default to zero.",
         "properties": {
            "id": {
               "title": "Id",
               "type": "string"
            },
            "type": {
               "enum": [
                  "BOX",
                  "SPHERE"
               ],
               "title": "Type",
               "type": "string"
            },
            "pose_frame": {
               "title": "Pose Frame",
               "type": "string"
            },
            "pose": {
               "$ref": "#/$defs/PoseModel"
            },
            "box": {
               "anyOf": [
                  {
                     "$ref": "#/$defs/PosePositionModel"
                  },
                  {
                     "type": "null"
                  }
               ],
               "default": null
            },
            "sphere": {
               "anyOf": [
                  {
                     "$ref": "#/$defs/SphereModel"
                  },
                  {
                     "type": "null"
                  }
               ],
               "default": null
            }
         },
         "required": [
            "id",
            "type",
            "pose_frame",
            "pose"
         ],
         "title": "RegionsOfInterestModel",
         "type": "object"
      },
      "SphereModel": {
         "description": "Used inside the RegionsOfInterestModel.",
         "properties": {
            "radius": {
               "title": "Radius",
               "type": "number"
            }
         },
         "required": [
            "radius"
         ],
         "title": "SphereModel",
         "type": "object"
      }
   },
   "required": [
      "region_of_interest"
   ]
}

Fields:
field region_of_interest: RegionsOfInterestModel [Required]