petercorke / robotics-toolbox-python

Robotics Toolbox for Python
MIT License
2.2k stars 460 forks source link

Integrating a new robot (UR10e) to the roboticstoolbox #353

Closed svenkatachalam closed 1 year ago

svenkatachalam commented 1 year ago

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)

# Shoulder pan to Base
E1 = rtb.ET.tz(0.1273)
E2 = rtb.ET.Rz()

# Shoulder link to shoulder pan
E3 = rtb.ET.ty(0.220941) * rtb.ET.Ry(np.pi / 2)
E4 = rtb.ET.Ry()

# Elbow to shoulder link
E5 = rtb.ET.ty(-0.1719) * rtb.ET.tz(0.612)
E6 = rtb.ET.Ry()

# Wrist 1 to Elbow
E7 = rtb.ET.tz(0.5723) * rtb.ET.Ry(np.pi / 2)
E8 = rtb.ET.Ry()

# Wrist 2 to Wrist 1
E9 = rtb.ET.ty(0.1149)
E10 = rtb.ET.Rz()

# Wrist 3 to Wrist 2
E11 = rtb.ET.tz(0.1157)
E12 = rtb.ET.Ry()
E13 = rtb.ET.ty(0.0922) * rtb.ET.Rz(np.pi / 2)

` 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 'ikine_LM'

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:

  1. When I printed the number of ETS' from standard UR10 model 'rtb.models.UR10().ets().m', I am getting the value to be 14. And to my model 18. I traced the way the standard UR10 model (rtb.models.UR10()) and wrote the ETS definition for my model. But the result is the same.
  2. Also I couldnt use ETS model for computing ik. I used DH model. But the results on forward kinematics between DH model (I defined) and standard models (rtb.models.UR10()) are differing.
  3. On the new defined UR10 ETS model, I am unable to use the method ik_lm_chan() or ik_lm_wampler() for computing the inverse kinematics. And with DH model, this method is giving output in range of e-270/e-310. Is there any specific way/format to describe this model for using this method, so that inverse kinematics function ik_lm_chan() or ik_lm_wampler() will work.
  4. And how to use URDF_read for a custom URDF model of a robot. By default, it searches for URDF file in "Lib\site-packages\rtbdata\xacro\". I want to read URDF from different folder.

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

jhavl commented 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.

jhavl commented 1 year ago

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.

jhavl commented 1 year ago

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)
jhavl commented 1 year ago

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:

jhavl commented 1 year ago

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``

        """