robokudo.utils.o3d_helper¶
Functions¶
|
We assume that positive z is 'up' |
|
|
|
|
|
|
|
Get a cv2.boundingRect which represents the space taken by a open3d boundingbox. |
|
|
|
Generate a binary mask image by projecting the input_cloud to the ref_image mask |
Create and return a new cam intrinsic by scaling an input cam_intrinsic |
|
|
|
|
Combine a list of clouds into a single PointCloud, respecting the set colors. |
Generate a pointcloud from an object mask, rgb and depth image. |
|
|
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, target_obb)¶
-
We assume that positive z is ‘up’
- robokudo.utils.o3d_helper.transform_obb_relative_to_obb_center(input_obb, target_obb, transform: numpy.typing.NDArray)¶
- robokudo.utils.o3d_helper.get_obb_from_size_and_transform(bb_size: numpy.typing.NDArray, transform: numpy.typing.NDArray) open3d.geometry.OrientedBoundingBox ¶
-
- Parameters:
-
bb_size – Numpy array with 3 elements for BoundingBox size in X,Y,Z
transform – 4x4 numpy array
- Returns:
-
o3d.geometry.OrientedBoundingBox
- robokudo.utils.o3d_helper.get_2d_corner_points_from_3d_bb(cas: robokudo.cas.CAS, object_bb: open3d.geometry.OrientedBoundingBox) cv2.boundingRect ¶
- robokudo.utils.o3d_helper.get_2d_bounding_rect_from_3d_bb(cas: robokudo.cas.CAS, object_bb: open3d.geometry.OrientedBoundingBox) cv2.boundingRect ¶
-
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 ¶
- robokudo.utils.o3d_helper.get_mask_from_pointcloud(input_cloud, ref_image, cam_intrinsics: open3d.camera.PinholeCameraIntrinsic, mask_scale_factor=None, crop_to_ref=None)¶
-
Generate a binary mask image by projecting the input_cloud to the ref_image mask
TODO: Use the actual cam info here and not the PrimeSenseDefault
- 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 ¶
-
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 –
scalex – Scale factor for width/x
scaley – Scale factor for height/y
- robokudo.utils.o3d_helper.o3d_cam_intrinsics_from_ros_cam_info(cam_info)¶
- robokudo.utils.o3d_helper.concatenate_clouds(clouds: list) open3d.geometry.PointCloud ¶
-
Combine a list of clouds into a single PointCloud, respecting the set colors.
- Parameters:
-
clouds – List of open3d.geometry.PointCloud
- Returns:
-
A single PointCloud, containing the same points and colors
- 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 ¶
-
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
max_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.
- robokudo.utils.o3d_helper.create_line_for_visualization(origin: list, target: list, color: list) 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:
-
o3d.geometry.LineSet
- robokudo.utils.o3d_helper.create_sphere_from_translation(origin: numpy.ndarray, color: list, radius: float)¶
-
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