Closed Ahrovan closed 1 year ago
@Ahrovan the depth images should be saved at 16bit png files. Are there any .png files in the images folder?
@Ezward no all *.jpg files (Screanshot sent above)
@Ahrovan This must have gotten broken when the tub format was updated.
Yes, I just checked the code; the data type for the png is not there. I can fix this tonight.
It is in version 4.1, but that saves the old tub format. I'll port the code snippet to latest at lunch and you can try on a branch.
elif typ == 'gray16_array':
# save np.uint16 as a 16bit png
img = Image.fromarray(np.uint16(val))
name = self.make_file_name(key, ext='.png')
img.save(os.path.join(self.path, name))
json_data[key]=name
That snipped needs to be added to tub_v2.py at around line 65, after the elif input_type == 'image_array':
clause.
@Ahrovan I went ahead and made that change. it is is this branch 1098-fix-saving-D435-depth-image. From inside your donkeycar repo folder you can checkout the branch it that should fix the problem git checkout 1098-fix-saving-D435-depth-image
Please give that a try and report back here on how it went. Thanks.
@Ezward thank you. I will check and send result here
@Ahrovan any results yet?
@Ezward Just modify ext to extension and for apply any filter from cv, change uint16 to uint8 (tub_v2.py)
elif input_type == 'gray16_array':
# save np.uint16 as a 16bit png
image = Image.fromarray(np.uint8(value))
name = Tub._image_file_name(self.manifest.current_index, key, extension='.png')
image_path = os.path.join(self.images_base_path, name)
image.save(image_path)
contents[key]=name
for cv ColorMap (realsense435i.py)
self.depth_image_r = np.asanyarray(depth_frame.get_data(), dtype=np.uint16) if self.enable_depth else None
self.depth_image= cv2.applyColorMap(cv2.convertScaleAbs(self.depth_image_r, alpha=0.01, beta=0), cv2.COLORMAP_JET)
cv2.COLORMAP_JET can use as parameter in myConfig.py.
and for modify image size (manage.py) need to add IMAGE_W and IMAGE_H and IMAGE_DEPTH here:
cam = RealSense435i(
enable_rgb=cfg.REALSENSE_D435_RGB,
enable_depth=cfg.REALSENSE_D435_DEPTH,
enable_imu=cfg.REALSENSE_D435_IMU,
device_id=cfg.REALSENSE_D435_ID)
The issue with uint8
is that it looses accuracy, that is why I am saving it as a png. So the depth image is not meant to be a human visible image; it is meant so that you can take any pixel in the RGB image and lookup up it's depth by reading it from the depth image.
cv2.convertScaleAbs() function returns uint8. In this case, np.uint16 gives an error. should be changed to uint8. The main problem is the need to use COLORMAP_JET or more precisely colormap. Yes, uint16 has better quality. But the problem is that the depth output does not have a suitable range, it must be corrected. Duplicate values can be seen on depth.
@Ahrovan "Duplicate values can be seen on depth" What do you mean? There will certainly be some pixels that have the same depth as others; that would be normal.
To be clear, the depth image is NOT a visualization. It is data. It is the depth of each pixel in the RGB image as a 12bit value.
You can see that the test program does create a visualization; https://github.com/autorope/donkeycar/blob/c4d90910e0e1b5056dc8961a09c7e5eb1ba18ffe/donkeycar/parts/realsense435i.py#L290
There is an issue though; I don't save off the depth scale; without the depth scale it can't be converted back into meters. The driver does print out the depth scale when it runs, but it is not saved anywhere. A better format would just save out a 2d array of floats which represent the depth in meters for each pixel in the RGB image.
This librealsense github issue has code to show how to convert the depth data to meters. That would be easy to do. So if we want we can save both a depth visualization image and the data array as depth im meters.
# Start streaming
profile = pipeline.start(config)
# Getting the depth sensor's depth scale (see rs-align example for explanation)
depth_sensor = profile.get_device().first_depth_sensor()
depth_scale = depth_sensor.get_depth_scale()
print("Depth Scale is: " , depth_scale)
try:
while True:
# Wait for a coherent pair of frames: depth and color
frames = pipeline.wait_for_frames()
depth_frame = frames.get_depth_frame()
color_frame = frames.get_color_frame()
if not depth_frame or not color_frame:
continue
# Convert images to numpy arrays
depth_image = np.asanyarray(depth_frame.get_data())
color_image = np.asanyarray(color_frame.get_data())
depth = depth_image[320,240].astype(float)
distance = depth * depth_scale
print ("Distance (m): ", distance )
The issue also indicates, "on all 400 Series camera models except D405 the default depth unit scale is 0.001. So if the pixel depth value was 6000 then 6000 x 0.01 would give a real-world distance of 6 meters." So we could use that value reliably. However it is probably better to just save the array a floats.
For now I'm going to save the data as-is, as a 16bit grayscale png. The data can be easilly loaded by opencv or other that will load a png and the resulting image can be queried by pixel to get the distance in centimeters of that pixel. See PR https://github.com/autorope/donkeycar/pull/1106
@Ahrovan can you confirm that the greyscale data is being saved using the branch? https://github.com/autorope/donkeycar/tree/1098-fix-saving-D435-depth-image
closed as unresponsive.
Please check this line name = Tub._image_file_name(self.manifest.current_index, key, extension='.png')
or name = Tub._image_file_name(self.manifest.current_index, key, ext='.png')
ext or extension ? (https://github.com/autorope/donkeycar/pull/1106) @Ezward
Hello
Only color_images are saved. Depth_image are not saved. Please suggest a simple solution. Thank you
Related My CAR CONFIG (D435i+donkey v4.4.dev4)
I see Depth_image clear in Code like this, but not saved