How to get the depth info/images with p.getCameraImage

Official Python bindings with a focus on reinforcement learning and robotics.
Post Reply
Emkey
Posts: 3
Joined: Thu Feb 03, 2022 12:45 pm

How to get the depth info/images with p.getCameraImage

Post by Emkey »

I am trying to get the images from the camera (Synthetic Camera RGB data and Synthetic Camera Depth data). I do get the RGB one, but the depth one is wrong. I cannot save it in a '.png' because of errors regarding the floats, so I save it in a '.tiff'.
The views of the camera I want to get
The views of the camera I want to get
image0.jpeg (1.35 MiB) Viewed 42329 times

Code: Select all

img = p.getCameraImage(224, 224, renderer=p.ER_BULLET_HARDWARE_OPENGL)
rgbBuffer = img[2] 
depthBuffer = img[3] # .astype(np.uint8) ?
rgbim = Image.fromarray(rgbBuffer)
depim = Image.fromarray(depthBuffer)
rgbim.save('test_img/rgbtest'+str(counter)+'.png')
depim.save('test_img/depth'+str(counter)+'.tiff')
I am not sure if I need to work with the view and projection matrixes (I have tried, no result). Maybe I am managing wrong the depth data (depthBuffer). My main goal would be to save a PNG as depth image, and a JPG (although it does not really matter rn). But I can't seem to find the error because everything is working fine. But the depth image is wrong for some reason...
msaid
Posts: 2
Joined: Wed Feb 09, 2022 10:15 am

Re: How to get the depth info/images with p.getCameraImage

Post by msaid »

I would like to help you but i would like to ask you please how can i make the synthetic and depth image work inside ?
Emkey
Posts: 3
Joined: Thu Feb 03, 2022 12:45 pm

Re: How to get the depth info/images with p.getCameraImage

Post by Emkey »

Of course! (I am more or less managing, using open3d btw).
Try adding these lines!
p.configureDebugVisualizer(p.COV_ENABLE_SEGMENTATION_MARK_PREVIEW, 1)
p.configureDebugVisualizer(p.COV_ENABLE_DEPTH_BUFFER_PREVIEW, 1)
p.configureDebugVisualizer(p.COV_ENABLE_RGB_BUFFER_PREVIEW, 1)
msaid
Posts: 2
Joined: Wed Feb 09, 2022 10:15 am

Re: How to get the depth info/images with p.getCameraImage

Post by msaid »

Thanks it runs but still no image i dont know why actually
Attachments
Capture.PNG
Capture.PNG (11.17 KiB) Viewed 42200 times
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA
Contact:

Re: How to get the depth info/images with p.getCameraImage

Post by Erwin Coumans »

The images display after calling 'getCameraImage'.

See https://github.com/bulletphysics/bullet ... nder_np.py

Here is a snippet that shows depth (requires matplotlib and numpy, next to pybullet)

Code: Select all

import matplotlib.pyplot as plt
import numpy as np
import pybullet as p
import pybullet_data as pd

p.connect(p.GUI)
p.setAdditionalSearchPath(pd.getDataPath())
p.loadURDF('plane.urdf')
p.loadURDF('cube_small.urdf', basePosition=[0.0, 0.0, 0.025])

width = 128
height = 128

fov = 60
aspect = width / height
near = 0.02
far = 1

view_matrix = p.computeViewMatrix([0, 0, 0.5], [0, 0, 0], [1, 0, 0])
projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far)

# Get depth values using the OpenGL renderer
images = p.getCameraImage(width, height, view_matrix, projection_matrix, renderer=p.ER_BULLET_HARDWARE_OPENGL)
depth_buffer_opengl = np.reshape(images[3], [width, height])
depth_opengl = far * near / (far - (far - near) * depth_buffer_opengl)

# Get depth values using Tiny renderer
images = p.getCameraImage(width, height, view_matrix, projection_matrix, renderer=p.ER_TINY_RENDERER)
depth_buffer_tiny = np.reshape(images[3], [width, height])
depth_tiny = far * near / (far - (far - near) * depth_buffer_tiny)

p.disconnect()

# Plot both images - should show depth values of 0.45 over the cube and 0.5 over the plane
plt.subplot(1, 2, 1)
plt.imshow(depth_opengl, cmap='gray', vmin=0, vmax=1)
plt.title('OpenGL Renderer')

plt.subplot(1, 2, 2)
plt.imshow(depth_tiny, cmap='gray', vmin=0, vmax=1)
plt.title('Tiny Renderer')

plt.show()
Post Reply