robokudo.utils.o3d_helper¶
Open3D helper utilities for Robokudo.
This module provides helper functions for working with Open3D geometries and cameras. It supports:
Oriented bounding box operations
Point cloud manipulation
Camera intrinsics handling
2D-3D projections
Visualization utilities
The module integrates with: * Open3D for 3D geometry operations * OpenCV for image operations * NumPy for numerical computations * ROS for camera info conversion
Functions¶
Place one oriented bounding box on top of another. |
|
Transform bounding box relative to another's center. |
|
Create oriented bounding box from size and transform. |
|
|
Project 3D bounding box corners to 2D image points. |
|
Get a cv2.boundingRect which represents the space taken by a open3d boundingbox. |
|
Draw 3D bounding box wireframe on image. |
|
Generate a binary mask image by projecting the input_cloud to the ref_image mask |
Scale camera intrinsics by x and y factors. |
|
Convert ROS CameraInfo to Open3D camera intrinsics. |
|
|
Combine multiple point clouds into one. |
Create point cloud from RGB-D images and mask. |
|
|
Create a LineSet that you can use to visualize a line between two points |
Create an o3d sphere for visualization. |
Module Contents¶
- robokudo.utils.o3d_helper.put_obb_on_target_obb(input_obb: open3d.geometry.OrientedBoundingBox, target_obb: open3d.geometry.OrientedBoundingBox) open3d.geometry.OrientedBoundingBox¶
-
Place one oriented bounding box on top of another.
Places input_obb on top of target_obb by aligning their centers and adjusting height based on extents. Assumes positive Z is up.
- Parameters:
-
input_obb – Bounding box to place
target_obb – Target bounding box to place on
- Returns:
-
Transformed input bounding box
- robokudo.utils.o3d_helper.transform_obb_relative_to_obb_center(input_obb: open3d.geometry.OrientedBoundingBox, target_obb: open3d.geometry.OrientedBoundingBox, transform_matrix: numpy.typing.NDArray) open3d.geometry.OrientedBoundingBox¶
-
Transform bounding box relative to another’s center.
- Parameters:
-
input_obb – Bounding box to transform
target_obb – Reference bounding box
transform_matrix – 4x4 transform matrix relative to target center
- Returns:
-
Transformed bounding box
- robokudo.utils.o3d_helper.get_obb_from_size_and_transform(bb_size: numpy.typing.NDArray, transform_matrix: numpy.typing.NDArray) open3d.geometry.OrientedBoundingBox¶
-
Create oriented bounding box from size and transform.
- Parameters:
-
bb_size – Numpy array with 3 elements for BoundingBox size in X,Y,Z
transform_matrix – 4x4 numpy array
- Returns:
-
Oriented bounding box
- robokudo.utils.o3d_helper.get_2d_corner_points_from_3d_bb(cas: robokudo.cas.CAS, object_bb: open3d.geometry.OrientedBoundingBox) cv2.typing.Rect¶
-
Project 3D bounding box corners to 2D image points.
- Parameters:
-
cas – CAS containing camera parameters
object_bb – 3D bounding box to project
- Returns:
-
Array of 2D corner points
- robokudo.utils.o3d_helper.get_2d_bounding_rect_from_3d_bb(cas: robokudo.cas.CAS, object_bb: open3d.geometry.OrientedBoundingBox) cv2.typing.Rect¶
-
Get a cv2.boundingRect which represents the space taken by a open3d boundingbox. Perspective projection and color2depth ratio is taken into account.
- Parameters:
-
cas –
object_bb –
- Returns:
-
cv2.boundingRect
- robokudo.utils.o3d_helper.draw_wireframe_of_obb_into_image(cas: robokudo.cas.CAS, image: numpy.typing.NDArray, obb: open3d.geometry.OrientedBoundingBox) None¶
-
Draw 3D bounding box wireframe on image.
Projects 3D box edges to image plane and draws lines.
- Parameters:
-
cas – CAS containing camera parameters
image – Image to draw on
obb – 3D bounding box to visualize
- robokudo.utils.o3d_helper.get_mask_from_pointcloud(input_cloud: open3d.geometry.PointCloud, ref_image: numpy.typing.NDArray, cam_intrinsics: open3d.camera.PinholeCameraIntrinsic, mask_scale_factor: float = None, crop_to_ref: bool = None) numpy.typing.NDArray¶
-
Generate a binary mask image by projecting the input_cloud to the ref_image mask
- Parameters:
-
input_cloud – 3d points which should be projected to the result maskimage
ref_image – A reference image for the dimensionality of the mask
cam_intrinsics – Camera intrinsics that have been used to generate input_cloud
mask_scale_factor – If your color and depth image size mismatch, l
you might have to scale your depth-based mask image to the dimensions of your color image. Please provide that factor here. Example: Kinect has 1280x images were as the depth images are only 640x . This would require a scale factor of 2.0 :param crop_to_ref: This is usually set to True, if mask_scale_factor has been set. Crop the result of the scale operation to the size of ref_image (0:height) and (0:width) :return: A binary mask image for OpenCV
- robokudo.utils.o3d_helper.scale_o3d_cam_intrinsics(cam_intrinsic: open3d.camera.PinholeCameraIntrinsic, scalex: float, scaley: float) open3d.camera.PinholeCameraIntrinsic¶
-
Scale camera intrinsics by x and y factors.
Create and return a new cam intrinsic by scaling an input cam_intrinsic based on a scale factor scalex and scaley. Scaling will be done by multipling the factor with the relevant properties. Example: new_height = height * scaley
- Parameters:
-
cam_intrinsic – Original camera intrinsics
scalex – Scale factor for width/x
scaley – Scale factor for height/y
- Returns:
-
Scaled camera intrinsics
- robokudo.utils.o3d_helper.o3d_cam_intrinsics_from_ros_cam_info(cam_info: sensor_msgs.msg.CameraInfo) open3d.camera.PinholeCameraIntrinsic¶
-
Convert ROS CameraInfo to Open3D camera intrinsics.
- Parameters:
-
cam_info – ROS camera info message
- Returns:
-
Open3D camera intrinsics
- robokudo.utils.o3d_helper.concatenate_clouds(clouds: typing_extensions.List[open3d.geometry.PointCloud]) open3d.geometry.PointCloud¶
-
Combine multiple point clouds into one.
Concatenates points and colors from input clouds.
- Parameters:
-
clouds – List of point clouds to combine
- Returns:
-
Combined point cloud
- robokudo.utils.o3d_helper.get_cloud_from_rgb_depth_and_mask(rgb_image: numpy.typing.NDArray, depth_image: numpy.typing.NDArray, mask: numpy.typing.NDArray, cam_intrinsics: open3d.camera.PinholeCameraIntrinsic, depth_truncate: float = 9.0, mask_true_val: int = 255) open3d.geometry.PointCloud¶
-
Create point cloud from RGB-D images and mask.
Generate a pointcloud from an object mask, rgb and depth image. Important: The depth_image will be changed when executing this function. Provide a copy if necessary.
- Constraints:
-
RGB, Depth image and Mask must be of the same resolution.
- Parameters:
-
rgb_image – An image in RGB order. Please note, that cv2 normally uses BGR order. So you have to convert first.
depth_image – A depth image
mask – a numpy array of dtype np.uint8
cam_intrinsics – Camera intrinsics for the rgb and depth image
depth_truncate – During cloud creation, ignore points beyond this many meters
mask_true_val – If the ‘mask’ contains a value equal to ‘max_true_val’, the corresponding value in ‘depth’
will be included. Otherwise it will be set to 0. :return: Point cloud from masked RGB-D data
Warning
The depth_image will be modified during processing. Provide a copy if original needs to be preserved.
- robokudo.utils.o3d_helper.create_line_for_visualization(origin: typing_extensions.Tuple[float, float, float], target: typing_extensions.Tuple[float, float, float], color: typing_extensions.Tuple[float, float, float]) open3d.geometry.LineSet¶
-
Create a LineSet that you can use to visualize a line between two points
- Parameters:
-
origin – 3 element list: [x,y,z]
target – 3 element list: [x,y,z]
color – 3 element list: [r,g,b]
- Returns:
-
Line segment geometry
- robokudo.utils.o3d_helper.create_sphere_from_translation(origin: numpy.typing.NDArray, color: typing_extensions.Tuple[float, float, float], radius: float) open3d.geometry.TriangleMesh¶
-
Create an o3d sphere for visualization.
- Parameters:
-
origin – 3d translation vector
color – 3 element list with entries 0-1 for RGB
radius – radius of sphere in meters
- Returns:
-
o3d sphere mesh