Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Joints order and MJCF to URDF #21

Open
JLBicho opened this issue Nov 21, 2024 · 0 comments
Open

Joints order and MJCF to URDF #21

JLBicho opened this issue Nov 21, 2024 · 0 comments

Comments

@JLBicho
Copy link

JLBicho commented Nov 21, 2024

Hi all,

First of all, great work!

I'm trying to get some stuff with ROS 2 and MoCapAct and I'm having some issues regarding the conversion from MJCF to URDF. Is there any script or converter tool that works with multi-joints bodies? I've tried some tools but they fail when it involves multi-joints. I've tried to convert by hand, but I'm not convinced it's completely correct (appended at the end of the issue).

Also, I'm trying to figure out the order of the joints in the in the hdf5 files. I understand there are 56 joints in hdf5_dset["observable_indices"]["walker"]["joints_pos"]. This joints are defined in cmu_humanoid.py:

_CMU_MOCAP_JOINTS = (
    'lfemurrz', 'lfemurry', 'lfemurrx', 'ltibiarx', 'lfootrz', 'lfootrx',
    'ltoesrx', 'rfemurrz', 'rfemurry', 'rfemurrx', 'rtibiarx', 'rfootrz',
    'rfootrx', 'rtoesrx', 'lowerbackrz', 'lowerbackry', 'lowerbackrx',
    'upperbackrz', 'upperbackry', 'upperbackrx', 'thoraxrz', 'thoraxry',
    'thoraxrx', 'lowerneckrz', 'lowerneckry', 'lowerneckrx', 'upperneckrz',
    'upperneckry', 'upperneckrx', 'headrz', 'headry', 'headrx', 'lclaviclerz',
    'lclaviclery', 'lhumerusrz', 'lhumerusry', 'lhumerusrx', 'lradiusrx',
    'lwristry', 'lhandrz', 'lhandrx', 'lfingersrx', 'lthumbrz', 'lthumbrx',
    'rclaviclerz', 'rclaviclery', 'rhumerusrz', 'rhumerusry', 'rhumerusrx',
    'rradiusrx', 'rwristry', 'rhandrz', 'rhandrx', 'rfingersrx', 'rthumbrz',
    'rthumbrx')

However, I also saw that some joints are used in a sorted order or inverse order:

self._actuator_order = np.argsort(_CMU_MOCAP_JOINTS)
self._inverse_order = np.argsort(self._actuator_order)

So my problem is that for joint at index 0 from hdf5_dset["observable_indices"]["walker"]["joints_pos"] I don't know if it's referring to

a. lfemurrz: from _CMU_MOCAP_JOINTS directly
b. headrx: from the _actuator_order list
c. rfemurrz: from the _inverse_order list

Any kind of help would be greatly appreciated!

Thanks in advance

humanoid.urdf

<robot name="humanoid_CMU">    
    <link name="world"/>
    <link name="root"/>
    
    <!-- llef_links -->
    <link name="lhipjoint">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lfemurx">
        <visual>
            <geometry>
                <cylinder length="0.5" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lfemury">
        <visual>
            <geometry>
                <cylinder length="0.5" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lfemurz">
        <visual>
            <geometry>
                <cylinder length="0.5" radius="0.12"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="ltibia">
        <visual>
            <geometry>
                <cylinder length="0.5" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lfootx">
    </link>
    <link name="lfootz">
        <visual>
            <geometry>
                <box size="0.15 0.3 0.15"/>
            </geometry>
            <material name="blue">
                <color rgba="0.0 0.0 1.0 1.0"/>
            </material>
            <origin xyz="0 0 0.07" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="ltoes">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
            <material name="red">
                <color rgba="1.0 0.0 0.0 1.0"/>
            </material>
        </visual>
    </link>

    <!-- rleg_links -->
    <link name="rhipjoint">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rfemurx">
        <visual>
            <geometry>
                <cylinder length="0.5" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rfemury">
        <visual>
            <geometry>
                <cylinder length="0.5" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rfemurz">
        <visual>
            <geometry>
                <cylinder length="0.5" radius="0.12"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rtibia">
        <visual>
            <geometry>
                <cylinder length="0.5" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rfootx">
    </link>
    <link name="rfootz">
        <visual>
            <geometry>
                <box size="0.15 0.3 0.15"/>
            </geometry>
            <origin xyz="0 0 0.07" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rtoes">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>

    <!-- body -->
    <link name="lowerbackx">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lowerbacky">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lowerbackz">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="upperbackx">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="upperbacky">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="upperbackz">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="thoraxx">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="thoraxy">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="thoraxz">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lowerneckx">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lowernecky">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lowerneckz">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="upperneckx">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="uppernecky">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="upperneckz">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="headx">
    </link>
    <link name="heady">
    </link>
    <link name="headz">
        <visual>
            <geometry>
                <sphere radius="0.15"/>
            </geometry>
            <origin xyz="0.0 0.1 0.0" rpy="0.0 0.0 0.0"/>
        </visual>
    </link>

    <!-- larm -->
    <link name="lclaviclez">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <material name="green">
                <color rgba="0.0 1.0 0.0 1.0"/>
            </material>
            <origin xyz="0.0918817 0.0382636 0.00535704" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lclavicley">
    </link>
    <link name="lhumerusx">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lhumerusy">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lhumerusz">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lradius">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lwrist">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lhandx">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lhandz">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lfingers">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lthumbx">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="lthumbz">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>

    <!-- rarm -->
    <link name="rclaviclez">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rclavicley">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rhumerusx">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rhumerusy">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rhumerusz">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rradius">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rwrist">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rhandx">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rhandz">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rfingers">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rthumbx">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
    <link name="rthumbz">
        <visual>
            <geometry>
                <cylinder length="0.1" radius="0.1"/>
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0"/>
        </visual>
    </link>
 
    <!-- root -->
    <joint name="root_j" type="fixed">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="world"/>
        <child link="root"/>
    </joint>

    <!-- lleg -->
    <joint name="lhipjoint_j" type="fixed">
        <origin xyz="0.0509685 -0.0459037 0.024723" rpy="0 0 0"/>
        <parent link="root"/>
        <child link="lhipjoint"/>
    </joint>

    <joint name="lfemurrz" type="revolute">
        <origin xyz="0.101937 -0.0918074 0.0494461" rpy="0 0 0"/>
        <parent link="lhipjoint"/>
        <child link="lfemurz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-1.0472" upper="1.22173" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lfemurry" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="lfemurz"/>
        <child link="lfemury"/>
        <axis xyz="0 1 0"/>
        <limit lower="-1.22173" upper="1.22173" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lfemurrx" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="lfemury"/>
        <child link="lfemurx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-2.79253" upper="0.349066" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="ltibiarx" type="revolute">
        <origin xyz="0 -0.404945 0" rpy="0 0 0"/>
        <parent link="lfemurx"/>
        <child link="ltibia"/>
        <axis xyz="1 0 0"/>
        <limit lower="0.01" upper="2.96706" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lfootrz" type="revolute">
        <origin xyz="0 -0.415693 0" rpy="0 0 0"/>
        <parent link="ltibia"/>
        <child link="lfootz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-1.22173" upper="0.349066" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lfootrx" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="lfootz"/>
        <child link="lfootx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-0.785398" upper="0.8" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="ltoesrx" type="revolute">
        <origin xyz="0 -0.156372 -0.0227756" rpy="0 0 0"/>
        <parent link="lfootx"/>
        <child link="ltoes"/>
        <axis xyz="1 0 0"/>
        <limit lower="-1.5708" upper="0.349066" effort="100.0" velocity="100.0"/>
    </joint>

    <!-- rleg -->

    <joint name="rhipjoint_j" type="fixed">
        <origin xyz="-0.0509685 -0.0459037 0.024723" rpy="0 0 0"/>
        <parent link="root"/>
        <child link="rhipjoint"/>
    </joint>

    <joint name="rfemurrz" type="revolute">
        <origin xyz="-0.101937 -0.0918074 0.0494461" rpy="0 0 0"/>
        <parent link="rhipjoint"/>
        <child link="rfemurz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-1.0472" upper="1.22173" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rfemurry" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="rfemurz"/>
        <child link="rfemury"/>
        <axis xyz="0 1 0"/>
        <limit lower="-1.22173" upper="1.22173" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rfemurrx" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="rfemury"/>
        <child link="rfemurx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-2.79253" upper="0.349066" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rtibiarx" type="revolute">
        <origin xyz="0 -0.404945 0" rpy="0 0 0"/>
        <parent link="rfemurx"/>
        <child link="rtibia"/>
        <axis xyz="1 0 0"/>
        <limit lower="0.01" upper="2.96706" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rfootrz" type="revolute">
        <origin xyz="0 -0.415693 0" rpy="0 0 0"/>
        <parent link="rtibia"/>
        <child link="rfootz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-1.22173" upper="0.349066" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rfootrx" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="rfootz"/>
        <child link="rfootx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-0.785398" upper="0.8" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rtoesrx" type="revolute">
        <origin xyz="0 -0.156372 -0.0227756" rpy="0 0 0"/>
        <parent link="rfootx"/>
        <child link="rtoes"/>
        <axis xyz="1 0 0"/>
        <limit lower="-1.5708" upper="0.349066" effort="100.0" velocity="100.0"/>
    </joint>

    <!-- body -->
    <joint name="lowerbackrz" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="root"/>
        <child link="lowerbackz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-0.523599" upper="0.523599" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lowerbackry" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="lowerbackz"/>
        <child link="lowerbacky"/>
        <axis xyz="0 1 0"/>
        <limit lower="-0.523599" upper="0.523599" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lowerbackrx" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="lowerbacky"/>
        <child link="lowerbackx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-0.349066" upper="0.785398" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="upperbackrz" type="revolute">
        <origin xyz="0.000565862 0.113213 -0.00805298" rpy="0 0 0"/>
        <parent link="lowerbackx"/>
        <child link="upperbackz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-0.523599" upper="0.523599" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="upperbackry" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="upperbackz"/>
        <child link="upperbacky"/>
        <axis xyz="0 1 0"/>
        <limit lower="-0.523599" upper="0.523599" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="upperbackrx" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="upperbacky"/>
        <child link="upperbackx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-0.349066" upper="0.785398" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="thoraxrz" type="revolute">
        <origin xyz="0.000512528 0.11356 0.000936821" rpy="0 0 0"/>
        <parent link="upperbackx"/>
        <child link="thoraxz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-0.523599" upper="0.523599" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="thoraxry" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="thoraxz"/>
        <child link="thoraxy"/>
        <axis xyz="0 1 0"/>
        <limit lower="-0.523599" upper="0.523599" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="thoraxrx" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="thoraxy"/>
        <child link="thoraxx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-0.349066" upper="0.785398" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lowerneckrz" type="revolute">
        <origin xyz="0 0.113945 0.00468037" rpy="0 0 0"/>
        <parent link="thoraxx"/>
        <child link="lowerneckz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-0.523599" upper="0.523599" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lowerneckry" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="lowerneckz"/>
        <child link="lowernecky"/>
        <axis xyz="0 1 0"/>
        <limit lower="-0.523599" upper="0.523599" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lowerneckrx" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="lowernecky"/>
        <child link="lowerneckx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-0.349066" upper="0.785398" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="upperneckrz" type="revolute">
        <origin xyz="0 0.113945 0.00468037" rpy="0 0 0"/>
        <parent link="lowerneckx"/>
        <child link="upperneckz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-0.523599" upper="0.523599" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="upperneckry" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="upperneckz"/>
        <child link="uppernecky"/>
        <axis xyz="0 1 0"/>
        <limit lower="-0.523599" upper="0.523599" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="upperneckrx" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="uppernecky"/>
        <child link="upperneckx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-0.349066" upper="0.785398" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="headrz" type="revolute">
        <origin xyz="0.00100175 0.13 -0.00449288" rpy="0 0 0"/>
        <parent link="upperneckx"/>
        <child link="headz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-0.523599" upper="0.523599" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="headry" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="headz"/>
        <child link="heady"/>
        <axis xyz="0 1 0"/>
        <limit lower="-0.523599" upper="0.523599" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="headrx" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="heady"/>
        <child link="headx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-0.349066" upper="0.785398" effort="100.0" velocity="100.0"/>
    </joint>

    <!-- larm -->
    <joint name="lclaviclerz" type="revolute">
        <origin xyz="0 0.113945 0.00468037" rpy="0 0 0"/>
        <parent link="thoraxx"/>
        <child link="lclaviclez"/>
        <axis xyz="0 0 1"/>
        <limit lower="0" upper="0.349066" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lclaviclery" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="lclaviclez"/>
        <child link="lclavicley"/>
        <axis xyz="0 1 0"/>
        <limit lower="-0.349066" upper="0.174533" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lhumerusrz" type="revolute">
        <origin xyz="0.18 0.09 0.0107141" rpy="0 0 0"/>
        <parent link="lclavicley"/>
        <child link="lhumerusz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-1.1" upper="1.5708" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lhumerusry" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="lhumerusz"/>
        <child link="lhumerusy"/>
        <axis xyz="0 1 0"/>
        <limit lower="-1.5708" upper="1.5708" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lhumerusrx" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="lhumerusy"/>
        <child link="lhumerusx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-1.0472" upper="1.5708" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lradiusrx" type="revolute">
        <origin xyz="0 -0.276843 0" rpy="0 0 0"/>
        <parent link="lhumerusx"/>
        <child link="lradius"/>
        <axis xyz="1 0 0"/>
        <limit lower="-0.174533" upper="2.96706" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lwristry" type="revolute">
        <origin xyz="0 -0.181536 0" rpy="0 0 0"/>
        <parent link="lradius"/>
        <child link="lwrist"/>
        <axis xyz="0 1 0"/>
        <limit lower="0" upper="3.14159" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lhandrz" type="revolute">
        <origin xyz="0 -0.0907676 0" rpy="0 0 0"/>
        <parent link="lwrist"/>
        <child link="lhandz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-0.785398" upper="0.785398" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lhandrx" type="revolute">
        <origin xyz="0 -0.0907676 0" rpy="0 0 0"/>
        <parent link="lhandz"/>
        <child link="lhandx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-1.5708" upper="1.5708" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lfingersrx" type="revolute">
        <origin xyz="0 0.015 0" rpy="0 0 0"/>
        <parent link="lhandx"/>
        <child link="lfingers"/>
        <axis xyz="1 0 0"/>
        <limit lower="0" upper="1.5708" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lthumbrz" type="revolute">
        <origin xyz="-.025 0 0" rpy="0 0 0"/>
        <parent link="lhandx"/>
        <child link="lthumbz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-0.785398" upper="0.785398" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="lthumbrx" type="revolute">
        <origin xyz="0 -0.0907676 0" rpy="0 0 0"/>
        <parent link="lthumbz"/>
        <child link="lthumbx"/>
        <axis xyz="1 0 0"/>
        <limit lower="0" upper="1.5708" effort="100.0" velocity="100.0"/>
    </joint>

    <!-- rarm -->
    <joint name="rclaviclerz" type="revolute">
        <origin xyz="0 0.113945 0.00468037" rpy="0 0 0"/>
        <parent link="thoraxx"/>
        <child link="rclaviclez"/>
        <axis xyz="0 0 1"/>
        <limit lower="0" upper="0.349066" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rclaviclery" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="rclaviclez"/>
        <child link="rclavicley"/>
        <axis xyz="0 1 0"/>
        <limit lower="-0.349066" upper="0.174533" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rhumerusrz" type="revolute">
        <origin xyz="-0.18 0.09 0.0107141" rpy="0 0 0"/>
        <parent link="rclavicley"/>
        <child link="rhumerusz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-1.1" upper="1.5708" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rhumerusry" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="rhumerusz"/>
        <child link="rhumerusy"/>
        <axis xyz="0 1 0"/>
        <limit lower="-1.5708" upper="1.5708" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rhumerusrx" type="revolute">
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <parent link="rhumerusy"/>
        <child link="rhumerusx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-1.0472" upper="1.5708" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rradiusrx" type="revolute">
        <origin xyz="0 -0.276843 0" rpy="0 0 0"/>
        <parent link="rhumerusx"/>
        <child link="rradius"/>
        <axis xyz="1 0 0"/>
        <limit lower="-0.174533" upper="2.96706" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rwristry" type="revolute">
        <origin xyz="0 -0.181536 0" rpy="0 0 0"/>
        <parent link="rradius"/>
        <child link="rwrist"/>
        <axis xyz="0 1 0"/>
        <limit lower="0" upper="3.14159" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rhandrz" type="revolute">
        <origin xyz="0 -0.0907676 0" rpy="0 0 0"/>
        <parent link="rwrist"/>
        <child link="rhandz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-0.785398" upper="0.785398" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rhandrx" type="revolute">
        <origin xyz="0 -0.0907676 0" rpy="0 0 0"/>
        <parent link="rhandz"/>
        <child link="rhandx"/>
        <axis xyz="1 0 0"/>
        <limit lower="-1.5708" upper="1.5708" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rfingersrx" type="revolute">
        <origin xyz="0 0.015 0" rpy="0 0 0"/>
        <parent link="rhandx"/>
        <child link="rfingers"/>
        <axis xyz="1 0 0"/>
        <limit lower="0" upper="1.5708" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rthumbrz" type="revolute">
        <origin xyz="-.025 0 0" rpy="0 0 0"/>
        <parent link="rhandx"/>
        <child link="rthumbz"/>
        <axis xyz="0 0 1"/>
        <limit lower="-0.785398" upper="0.785398" effort="100.0" velocity="100.0"/>
    </joint>

    <joint name="rthumbrx" type="revolute">
        <origin xyz="0 -0.0907676 0" rpy="0 0 0"/>
        <parent link="rthumbz"/>
        <child link="rthumbx"/>
        <axis xyz="1 0 0"/>
        <limit lower="0" upper="1.5708" effort="100.0" velocity="100.0"/>
    </joint>
</robot>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

1 participant