sim.generateIKpath is returning nill

Typically: "How do I... ", "How can I... " questions
Post Reply
alix
Posts: 62
Joined: 17 Sep 2019, 14:48

sim.generateIKpath is returning nill

Post by alix »

Hi Everyone,

I am keeping the "8-computingJointAnglesForRandomPoses.ttt" scene as model.
I have only 'LBR4p' robot and its targets at same positions as in that scene. The 'sim.getConfigforTipPose' returns configurations for the target, but "sim.generateIKpath" is giving me a null path everytime. Even though we have seen that these targets are reachable.

Code: Select all

function sysCall_threadmain()
     jh={-1,-1,-1,-1,-1,-1,-1}
    for i=1,7,1 do
        jh[i]=sim.getObjectHandle('j'..i)
    end
    ikGroup=sim.getIkGroupHandle('ik')
    ikTarget=sim.getObjectHandle('target')
    targets={sim.getObjectHandle('testTarget5'),sim.getObjectHandle('testTarget6'),sim.getObjectHandle('testTarget7'),sim.getObjectHandle('testTarget8')}
    cnt1=0
    cnt2=0
    steps=50
    local dummyHandle=targets[cnt1+1]
    local m=sim.getObjectMatrix(dummyHandle,-1)
    sim.setObjectMatrix(ikTarget,-1,m)
    --state=sim.getConfigForTipPose(ikGroup,jh,0.5,100)
    --print(state)
    c=sim.generateIkPath(ikGroup, jh, steps)
    printToConsole('The path is:', c)
This is my simple code. and my scene is uploaded at https://www.dropbox.com/s/cq66zq2hmwiml ... t.ttt?dl=0

I really do need help. Please Thanks.

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

Re: sim.generateIKpath is returning nill

Post by coppelia »

Your scene does not include any function sim.generateIKpath.
Then, make sure your joints are in the correct mode (i.e. inverse kinematics, not hybrid)
Also, for given tooltip pose, there is an infinity of configurations possible. Some configurations are close to a joint limit, and won't allow for movement along a straight line for instance.

You will have to try in a loop: pick a configuration for your pose, then check if you can move from that configuration in a straight line to another pose. If that doesn't work, pick another configuration for that pose, etc.

Cheers

alix
Posts: 62
Joined: 17 Sep 2019, 14:48

Re: sim.generateIKpath is returning nill

Post by alix »

coppelia wrote: 03 Oct 2019, 13:13 Your scene does not include any function sim.generateIKpath.
Then, make sure your joints are in the correct mode (i.e. inverse kinematics, not hybrid)
Also, for given tooltip pose, there is an infinity of configurations possible. Some configurations are close to a joint limit, and won't allow for movement along a straight line for instance.

You will have to try in a loop: pick a configuration for your pose, then check if you can move from that configuration in a straight line to another pose. If that doesn't work, pick another configuration for that pose, etc.

Cheers
I have disabled the 'sim.getConfigforTipPose' portion.

I am just taking object matrix of Target, and setting IKTarget as that matrix. and then just asking "sim.generateIKpath" to generate a path but it is returning nill ???? Joints are in IK mode and i have unchecked the hybrid option. still same nill return. Am I using sim.generateIKPath in a wrong manner ????

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

Re: sim.generateIKpath is returning nill

Post by coppelia »

Try this one: it uses both sim.getConfigForTipPose and sim.generateIkPath.

Code: Select all

applyJoints=function(jointHandles,joints)
    for i=1,#jointHandles,1 do
        sim.setJointPosition(jointHandles[i],joints[i])
    end
end

function sysCall_threadmain()
     jh={-1,-1,-1,-1,-1,-1,-1}
    for i=1,7,1 do
        jh[i]=sim.getObjectHandle('j'..i)
    end
    ikGroup=sim.getIkGroupHandle('ik')
    ikTarget=sim.getObjectHandle('target')
    targets={sim.getObjectHandle('testTarget5'),sim.getObjectHandle('testTarget6'),sim.getObjectHandle('testTarget7'),sim.getObjectHandle('testTarget8')}
    
    for j=1,#targets,1 do

        local dummyHandle=targets[j]
        local m=sim.getObjectMatrix(dummyHandle,-1)
        sim.setObjectMatrix(ikTarget,-1,m)
        state=sim.getConfigForTipPose(ikGroup,jh,0.5,100)
        if state then
            applyJoints(jh,state)
            local dist=0.2
            local m=sim.getObjectMatrix(ikTarget,-1)
            m[4]=m[4]+m[3]*dist
            m[8]=m[8]+m[7]*dist
            m[12]=m[12]+m[11]*dist
            sim.setObjectMatrix(ikTarget,-1,m)
            local path=sim.generateIkPath(ikGroup,jh,25)
            print(path)
            for i=0,(#path-1)/7,1 do
                local state={path[7*i+1],path[7*i+2],path[7*i+3],path[7*i+4],path[7*i+5],path[7*i+6],path[7*i+7]}
                applyJoints(jh,state)
                sim.switchThread()
            end
        end
    end
end
Cheers

Post Reply