Closed svenkatachalam closed 1 year ago
Hi @svenkatachalam, I'll do my best to figure out whats going on here.
Answer to Q1: When you get the ets() of a robot, it is getting a single sequence of transforms from the default start link to the default end link. As the UR10 URDF model has branches, the total number of ETs resulting from ets() will be less than the total number of ETs within the whole robot model.
Answer to Q2: it looks like the model definitions for the DH and URDF versions of the UR10 are slightly different. If you know if one is definitely right or wrong please raise a new issue. This difference in model will cause differences in the fkine solution.
Answer to top Q _And when I tried with computing inverse kinematics (for UR10), the solution is not correct with the provided ETS model. I would like to know, if we can work with ETS definitions for computing inverse kinematics I got the following error: AttributeError: 'ETS' object has no attribute 'ikineLM'
I think something may have been fixed since you raised this issue. This code works fine for me (note that the ik_lm_chan, ik_lm_wampler, and ik_lm_sugihara methods have been merged into ik_LM)
r = rtb.models.UR10()
Tep = sm.SE3.Trans(0.5, 0.2, 0.1) @ sm.SE3.OA([0, 1, 0], [0, 0, -1])
# Solve using Python based solver (is Chan's method by default)
sol1 = r.ets().ikine_LM(Tep)
# Solve using C based solver (is Chan's method by default)
sol2 = r.ets().ik_LM(Tep)
print(sol1)
IKSolution: q=[0.06031, -1.121, 2.062, -0.9414, -1.51, 0], success=True, iterations=10, searches=1, residual=4.09e-07
print(sol2)
(array([ 0.05939069, 1.19892355, -2.04316114, -2.29732724, 1.51138356,
-3.1415185 ]), 1, 16, 1, 4.5074648921724204e-07)
Answer to Q3:
There was a bug with the C-based IK solvers for robots initialised with no joint limits. I have fixed this and will be included in the next release. As previously mentioned:
Answer to Q4: use the method Robot.URDF_read, see docstring
"""
Read a URDF file as Links
File should be specified relative to ``RTBDATA/URDF/xacro``
Parameters
----------
file_path
File path relative to the xacro folder
tld
A custom top-level directory which holds the xacro data,
defaults to None
xacro_tld
A custom top-level within the xacro data,
defaults to None
Returns
-------
links
a list of links
name
the name of the robot
urdf
a string representing the URDF
file_path
a path to the original file
Notes
-----
If ``tld`` is not supplied, filepath pointing to xacro data should
be directly under ``RTBDATA/URDF/xacro`` OR under ``./xacro`` relative
to the model file calling this method. If ``tld`` is supplied, then
```file_path``` needs to be relative to ``tld``
"""
I am new to roboticstoolbox and I am working on defining the UR10e robot model in ETS and DH format. As I dont have standard moedl to validate the results, I redescribed ETS of UR10 in a new file and compared with the standard model. For computing forward kinematics the ETS model is working fine. ` E0 = rtb.ET.Rz(0)
` And when I tried with computing inverse kinematics (for UR10), the solution is not correct with the provided ETS model. I would like to know, if we can work with ETS definitions for computing inverse kinematics I got the following error:
I tried with DH representation of the same robot and used same algorithm to compute ik and it worked. The output is still not correct as it prints "success=False" and the max iterations of 100 is reached. As I understand from other posts, this method will provide only the first outcome and not the all possible ik outputs.
I have following questions:
I have attached all the different format of the UR10 description in this post. Other than the representation with DH (test_DH.py) computing the inverse kinematics with other formats doesnt give correct solution.
test_e_ur10.txt test_ur10.txt test_ur10_new_ets.txt test_DH.txt