Problem about the rpy at joint element in urdf model

asked 2016-09-07 21:58:51 -0500

cangjiaxuan gravatar image

I write a very simple two link arm model, but I meet some strange problem.

Here is my model:

<?xml version="1.0"?>
<robot name="test_torque" xmlns:xacro="http://ros.org/wiki/xacro">

    <material name="orange">
        <color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
    </material>

    <gazebo reference="link1">
        <material>Gazebo/Orange</material>
    </gazebo>

    <gazebo reference="link2">
        <material>Gazebo/Orange</material>
    </gazebo>


    <xacro:property name="height1" value="0.2" />
    <xacro:property name="height2" value="0.1" />
    <xacro:property name="width" value="0.02" />
    <xacro:property name="mass" value="1" />
    <xacro:property name="PI" value="3.14" />

    <link name="world"/>

    <joint name="link1_to_world" type="fixed">
        <parent link="world"/>
        <child link="link1"/>
    </joint>

    <link name="link1">
        <visual>
            <origin xyz="0 0 ${height1/2}" rpy="0 0 0"/>
            <geometry>
                <box size="${width} ${width} ${height1}"/>
            </geometry>
            <material name="orange"/>
        </visual>

        <collision>
            <origin xyz="0 0 ${height1/2}" rpy="0 0 0"/>
            <geometry>
                <box size="${width} ${width} ${height1}"/>
            </geometry>
        </collision>

        <inertial>
            <origin xyz="0 0 ${height1/2}" rpy="0 0 0"/>
            <mass value="${mass}"/>
            <inertia 
                ixx="${height1*height1*mass/12}" ixy="0" ixz="0" 
                iyy="0" iyz="0"  
                izz="${height1*height1*mass/12}" />
        </inertial>
    </link>

<!--
    <joint name="link1_to_link2" type="continuous">
        <parent link="link1"/>
        <child link="link2"/>
        <origin xyz="${0.5*height2-0.5*width} 0 ${height1+0.5*width}" rpy="0 ${0.5*PI} 0"/>
        <axis xyz="0 1 0"/>
        <dynamics damping="0.7"/>
    </joint>
-->
    <joint name="link1_to_link2" type="continuous">
        <parent link="link1"/>
        <child link="link2"/>
        <origin xyz="${0.5*height2-0.5*width} 0 ${height1+0.5*width}" rpy="${0.5*PI} 0 0"/>
        <axis xyz="0 1 0"/>
        <dynamics damping="0.7"/>
    </joint>

    <link name="link2">

        <visual>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <box size="${width} ${width} ${height2}"/>
            </geometry>
            <material name="orange"/>
        </visual>

        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <box size="${width} ${width} ${height2}"/>
            </geometry>
        </collision>

        <inertial>
            <origin xyz="0 0 0 " rpy="0 0 0"/>
            <mass value="${mass}"/>
            <inertia
                ixx="${height2*height2*mass/12}" ixy="0" ixz="0"
                iyy="0" iyz="0"
                izz="${height2*height2*mass/12}"
                />
        </inertial>
    </link>

</robot>

When I use the model in the comment every thing is fine, but when I use the model now, it appears that the second link would go below the first link. Why does this happens?

edit retag flag offensive close merge delete