generating ikfast for 7 DoF Kuka lwr

classic Classic list List threaded Threaded
1 message Options
Reply | Threaded
Open this post in threaded view
|  
Report Content as Inappropriate

generating ikfast for 7 DoF Kuka lwr

xelda1988
Hey guys

I have trouble creating the ikfast plugin for our 7 DoF robot.  
I already created a .dae file from the ROS urdf_collada converter.

The file seems to be fine:
robot_model

I want to create an ik solution which is rooted in the world_link as BASE_link and has the  right_sdh_connector_link as TOOL_LINK. Also I want to have the third right_arm_3_link as a --freeindex.
Here a part of the output of

   openrave-robot.py iis_robot_table.rounded.dae --info links

...
calib_right_arm_base_link 32    world_link              
right_arm_base_link       33    calib_right_arm_base_link
right_arm_1_link          34    right_arm_base_link      
right_arm_2_link          35    right_arm_1_link        
right_arm_3_link          36    right_arm_2_link        
right_arm_4_link          37    right_arm_3_link        
right_arm_5_link          38    right_arm_4_link        
right_arm_6_link          39    right_arm_5_link        
right_arm_7_link          40    right_arm_6_link        
right_sdh_connector_link  41    right_arm_7_link
...


But there is no chance to specify a linkchain containing e.g 33 as BASE_LINK with 40 as EE_LINK. Basically the output of the following command is:

   python `openrave-config --python-dir`/openravepy/_openravepy_/ikfast.py --robot=iis_robot_table.rounded.dae  -iktype=transform6d --baselink=33 --eelink=40 --freeindex=36 --savefile=ikfast61_right_arm.cpp

Gives me:

Traceback (most recent call last):
  File "/usr/lib/python2.7/dist-packages/openravepy/_openravepy_/ikfast.py", line 6121, in <module>
    chaintree = solver.generateIkSolver(options.baselink,options.eelink,options.freeindices,solvefn=solvefn)
  File "/usr/lib/python2.7/dist-packages/openravepy/_openravepy_/ikfast.py", line 1639, in generateIkSolver
    chaintree = solvefn(self, LinksRaw, jointvars, isolvejointvars)
  File "/usr/lib/python2.7/dist-packages/openravepy/_openravepy_/ikfast.py", line 2104, in solveFullIK_6D
    raise self.CannotSolveError('need 6 joints')
__main__.CannotSolveError: 'need 6 joints'


I can only specify chains which have 6 links.

What can I do?

Cheers,
Alex
Loading...