How to draw the point cloud for the end-effector trajectory of the manipulator in scece?

Typically: "How do I... ", "How can I... " questions
Post Reply
zhangm365
Posts: 46
Joined: 19 Jun 2021, 12:58

How to draw the point cloud for the end-effector trajectory of the manipulator in scece?

Post by zhangm365 »

Dear admin:
Can we draw the point cloud only for the end point trajectory of the manipulator?
For example, as the picture shown, the red point or green point:

Image


Best wishes.

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

Re: How to draw the point cloud for the end-effector trajectory of the manipulator in scece?

Post by coppelia »

Hello,

did you try sim.insertPointsIntoPointCloud?

e.g.:

Code: Select all

function sysCall_init()
    pc=sim.createPointCloud(0.01,1000,0,2)
end

function sysCall_sensing()
    local t=sim.getSimulationTime()
    local pt={math.sin(t),math.sin(3*t),math.sin(5*t)}
    sim.insertPointsIntoPointCloud(pc,2,pt,{255,0,255})
end
Cheers

zhangm365
Posts: 46
Joined: 19 Jun 2021, 12:58

Re: How to draw the point cloud for the end-effector trajectory of the manipulator in scece?

Post by zhangm365 »

Yeah, I try to show the position changes for the point cloud.

Code: Select all

function sysCall_init()
    pc=sim.createPointCloud(0.01,1000,0,2)
    modelHandle = sim.getObject('/LBR_iiwa_7_R800')
    targetHandle = sim.getObject('/target')
end

function sysCall_sensing()
    local t=sim.getSimulationTime()
    local p = sim.getObjectPosition(targetHandle, modelHandle)
    local pt={p[1], p[2], p[3]}
    sim.insertPointsIntoPointCloud(pc,2,pt,{255,0,255})
end
But, the points are too dense, can we make the dots sparse to display?

Best wishes.

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

Re: How to draw the point cloud for the end-effector trajectory of the manipulator in scece?

Post by coppelia »

Look at sim.createPointCloud's second argument. But if you only want to display points, you can also do it with drawing objects:

Code: Select all

function sysCall_init()
    local duplicateTolerance=0.001
    dr=sim.addDrawingObject(sim.drawing_points|sim.drawing_cyclic,2,duplicateTolerance,-1,0,{1,0,1})
end

function sysCall_sensing()
    local t=sim.getSimulationTime()
    local pt={math.sin(t),math.sin(3*t),math.sin(5*t)}
    sim.addDrawingObjectItem(dr,pt)
end
Cheers

zhangm365
Posts: 46
Joined: 19 Jun 2021, 12:58

Re: How to draw the point cloud for the end-effector trajectory of the manipulator in scece?

Post by zhangm365 »

OK, the effects displayed in these two ways are very familiar.

How can the dot map of the position information be displayed in a separate window?

Besides, How can the position images of two different dummy nodes in the same scene be drawn in a separate image window?

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

Re: How to draw the point cloud for the end-effector trajectory of the manipulator in scece?

Post by coppelia »

You'll have to add a camera with lights at a different location, and open a floating view to look through that camera.

Cheers

Post Reply