Getting Depth Image

Typically: "How do I... ", "How can I... " questions
Post Reply
major_david
Posts: 14
Joined: 16 Jun 2023, 18:44

Getting Depth Image

Post by major_david »

Hi everyone,

I'm trying to get the depth image taken by the vision sensor with an external Python script. I followed the steps provided in the previous questions in this forum. However, I cannot still retrieve the image I want.
The procedure I follow in the external script is like this:
First, the vision sensor is activated by using "detectionCount,_,_= sim.handleVisionSensor(visionSensorHandle)". Then the depth buffer is retrieved using: "depth, res = sim.getVisionSensorDepth(visionSensorHandle,0,[0,0],[0,0])"
After that, according to the documentation on the website, this buffer is unpacked using: "unpackedDepth = sim.unpackFloatTable(depth, 0,0,0)"
However, I have two problems right now:
1) the unpacked depth list does not make sense, and all the values in this list are the same, and the format of how the values are stored is not clear.
2) the unpacking process takes a long time, around 10 seconds, which is not good for my project.

Also, the child script for the vision sensor in the scene is like this:

"--lua
sim=require'sim'
simVision=require'simVision'
function sysCall_init()
end
function sysCall_vision(inData)
local retVal={}
retVal.trigger=false
retVal.packedPackets={}
simVision.sensorDepthMapToWorkImg(inData.handle)
simVision.intensityScaleOnWorkImg(inData.handle,1.000000,0.000000,false)
simVision.workImgToSensorImg(inData.handle)
return retVal
end
"
All I need is the depth information in a 2D array in the range of 0-255.

coppelia
Site Admin
Posts: 10375
Joined: 14 Dec 2012, 00:25

Re: Getting Depth Image

Post by coppelia »

Hello,

from an external Python script, simply get inspired from the demo <CoppeliaSim folder>/programming/zmqRemoteApi/clients/python/synchronousImageTransmission.py. Instead of calling sim.getVisionSensorImg in there, call sim.getVisionSensorDepth.

Keep in mind that in the associated scene file, the vision sensor ignores the depth map. You will have to uncheck the Ignore depth info (faster) checkbox for sim.getVisionSensorDepth to return meaningful information.

Cheers

major_david
Posts: 14
Joined: 16 Jun 2023, 18:44

Re: Getting Depth Image

Post by major_david »

coppelia wrote: 02 Dec 2023, 16:19 Hello,

from an external Python script, simply get inspired from the demo <CoppeliaSim folder>/programming/zmqRemoteApi/clients/python/synchronousImageTransmission.py. Instead of calling sim.getVisionSensorImg in there, call sim.getVisionSensorDepth.

Keep in mind that in the associated scene file, the vision sensor ignores the depth map. You will have to uncheck the Ignore depth info (faster) checkbox for sim.getVisionSensorDepth to return meaningful information.

Cheers
Thanks,

Just one more question, could you explain what the output is here? I mean the "img" parameter.
I get this while trying to understand what this output means: "Type image is <class 'bytes'> and the length is 1228800"
Do I still need to handle (perform sensing, etc. of) a vision sensor object according to the documentation?

coppelia
Site Admin
Posts: 10375
Joined: 14 Dec 2012, 00:25

Re: Getting Depth Image

Post by coppelia »

In Python, the function sim.getVisionSensorDepth returns bytes that you need to unpack if you want to interpret that data:

Code: Select all

import array

depth, res = sim.getVisionSensorDepth(visionSensorHandle)
float_array = array.array('f')
float_array.frombytes(depth)
depthValues = list(float_array)
In above code, depthValues is a list of res[0]*res[1] values, where each represents a depth value: a value of 0.0 represents the near clipping plane, a value of 1.0 represents the far clipping plane for that sensor.

If instead you need depth values in meters, then call sim.getVisionSensorDepth with an argument 2 that has bit0 set (i.e. 1)

Cheers

major_david
Posts: 14
Joined: 16 Jun 2023, 18:44

Re: Getting Depth Image

Post by major_david »

coppelia wrote: 04 Dec 2023, 08:47 In Python, the function sim.getVisionSensorDepth returns bytes that you need to unpack if you want to interpret that data:

Code: Select all

import array

depth, res = sim.getVisionSensorDepth(visionSensorHandle)
float_array = array.array('f')
float_array.frombytes(depth)
depthValues = list(float_array)
In above code, depthValues is a list of res[0]*res[1] values, where each represents a depth value: a value of 0.0 represents the near clipping plane, a value of 1.0 represents the far clipping plane for that sensor.

If instead you need depth values in meters, then call sim.getVisionSensorDepth with an argument 2 that has bit0 set (i.e. 1)

Cheers
Thanks, it worked.
Also, this method of unpacking is faster than the sim.unpackFloatTable function.
Cheers

Post Reply