File size: 4,168 Bytes
c882b43 0d57cff c882b43 0d57cff c882b43 0d57cff c882b43 0d57cff c882b43 0d57cff c882b43 |
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 |
<?xml version="1.0"?>
<robot name="chain_test">
<!-- Material definition -->
<material name="Grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<!-- Base link -->
<link name="base">
<inertial>
<mass value="10.0"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<!-- Chain 1: base -> fixed_1 -> fixed_2 -> fixed_3 -> revolute -> arm -->
<joint name="fix_j1" type="fixed">
<origin xyz="0.1 0 0" rpy="0.3 0 0"/>
<parent link="base"/>
<child link="fixed_1"/>
</joint>
<link name="fixed_1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.02" length="0.05"/>
</geometry>
<material name="Grey"/>
</visual>
<inertial>
<mass value="1.0"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/>
</inertial>
</link>
<joint name="fix_j2" type="fixed">
<origin xyz="0.1 0 0" rpy="0 0.4 0"/>
<parent link="fixed_1"/>
<child link="fixed_2"/>
</joint>
<link name="fixed_2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.025" length="0.05"/>
</geometry>
<material name="Grey"/>
</visual>
<inertial>
<mass value="2.0"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/>
</inertial>
</link>
<joint name="fix_j3" type="fixed">
<origin xyz="0.1 0 0" rpy="0 0 0.5"/>
<parent link="fixed_2"/>
<child link="fixed_3"/>
</joint>
<link name="fixed_3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.03" length="0.05"/>
</geometry>
<material name="Grey"/>
</visual>
<inertial>
<mass value="3.0"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/>
</inertial>
</link>
<joint name="shoulder" type="revolute">
<origin xyz="0.4 0 0" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<parent link="fixed_3"/>
<child link="arm"/>
<limit lower="-3.14" upper="3.14" effort="100.0" velocity="2.0"/>
</joint>
<link name="arm">
<visual>
<origin xyz="0 0 0.25" rpy="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.5"/>
</geometry>
<material name="Grey"/>
</visual>
<inertial>
<mass value="5.0"/>
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.01"/>
</inertial>
</link>
<!-- Chain 2: arm -> adapter_1 -> adapter_2 -> prismatic -> slider -->
<joint name="adapt_j1" type="fixed">
<origin xyz="0 0 0.5" rpy="0.1 0.0 0.2"/>
<parent link="arm"/>
<child link="adapter_1"/>
</joint>
<link name="adapter_1">
<visual>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.03" length="0.1"/>
</geometry>
<material name="Grey"/>
</visual>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
</inertial>
</link>
<joint name="adapt_j2" type="fixed">
<origin xyz="0 0 0.1" rpy="0 0.3 0"/>
<parent link="adapter_1"/>
<child link="adapter_2"/>
</joint>
<link name="adapter_2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="0.04"/>
</geometry>
<material name="Grey"/>
</visual>
<inertial>
<mass value="0.3"/>
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
</inertial>
</link>
<joint name="slider" type="prismatic">
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="adapter_2"/>
<child link="end_effector"/>
<limit lower="0.0" upper="0.5" effort="50.0" velocity="1.0"/>
</joint>
<link name="end_effector">
<visual>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<box size="0.06 0.06 0.2"/>
</geometry>
<material name="Grey"/>
</visual>
<inertial>
<mass value="2.0"/>
<inertia ixx="0.02" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.005"/>
</inertial>
</link>
</robot> |