ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

To generate IKFast solver C++ output file use the same generated collada file in following command -

pythonopenrave-config --python-dir/openravepy/_openravepy_/ikfast.py --robot=<myrobot_name>.dae --iktype=transform6d --baselink=1 --eelink=8 --savefile=<ikfast_output_path>

Whereas this results into segmentation fault and to generate the C++ output file regardless the segfault you will have to change the last block of code in ikfast.py file

solvefn=IKFastSolver.GetSolvers()[options.iktype.lower()]
if options.robot is not None:
    try:
        env=openravepy.Environment()
        kinbody=env.ReadRobotXMLFile(options.robot)
        env.Add(kinbody)
        solver = IKFastSolver(kinbody,kinbody)
        solver.maxcasedepth = options.maxcasedepth
        chaintree = solver.generateIkSolver(options.baselink,options.eelink,options.freeindices,solvefn=solvefn)
        code=solver.writeIkSolver(chaintree,lang=options.lang)
    finally:
        openravepy.RaveDestroy()

if len(code) > 0:
    with open(options.savefile,'w') as f:
        f.write(code)

to

solvefn=IKFastSolver.GetSolvers()[options.iktype.lower()]
if options.robot is not None:
    try:
        env=openravepy.Environment()
        kinbody=env.ReadRobotXMLFile(options.robot)
        env.Add(kinbody)
        solver = IKFastSolver(kinbody,kinbody)
        solver.maxcasedepth = options.maxcasedepth
        chaintree = solver.generateIkSolver(options.baselink,options.eelink,options.freeindices,solvefn=solvefn)
        code=solver.writeIkSolver(chaintree,lang=options.lang)
        if len(code) > 0:
            with open(options.savefile,'w') as f:
                f.write(code)
    finally:
        openravepy.RaveDestroy()

this bypasses the segfault and generates the desired ik solver file.