TwoJointRobot_w_fixedJoints.urdf 5.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182
  1. <?xml version="1.0" ?>
  2. <!-- =================================================================================== -->
  3. <!-- | This document was autogenerated by xacro from TwoJointRobot.xacro | -->
  4. <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
  5. <!-- =================================================================================== -->
  6. <robot name="TwoJointRobot" xmlns:xacro="http://www.ros.org/wiki/xacro">
  7. <material name="blue">
  8. <color rgba="0 0 0.8 1"/>
  9. </material>
  10. <material name="white">
  11. <color rgba="1 1 1 1"/>
  12. </material>
  13. <link name="base_link">
  14. <visual>
  15. <geometry>
  16. <cylinder length="0.05" radius="0.075"/>
  17. </geometry>
  18. <origin rpy="0 0 0" xyz="0 0 0.025"/>
  19. </visual>
  20. <collision>
  21. <geometry>
  22. <cylinder length="0.05" radius="0.075"/>
  23. </geometry>
  24. <origin rpy="0 0 0" xyz="0 0 0.025"/>
  25. </collision>
  26. <inertial>
  27. <mass value="0.2"/>
  28. <inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
  29. </inertial>
  30. </link>
  31. <link name="link_01_cyl">
  32. <visual>
  33. <geometry>
  34. <cylinder length="0.05" radius="0.075"/>
  35. </geometry>
  36. <origin rpy="0 0 0" xyz="0 0 0"/>
  37. <material name="blue"/>
  38. </visual>
  39. <collision>
  40. <geometry>
  41. <cylinder length="0.05" radius="0.075"/>
  42. </geometry>
  43. <origin rpy="0 0 0" xyz="0 0 0"/>
  44. </collision>
  45. <inertial>
  46. <mass value="0.2"/>
  47. <inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
  48. </inertial>
  49. </link>
  50. <link name="link_12_cyl">
  51. <visual>
  52. <geometry>
  53. <cylinder length="0.05" radius="0.075"/>
  54. </geometry>
  55. <origin rpy="0 0 0" xyz="0 0 0"/>
  56. <material name="blue"/>
  57. </visual>
  58. <collision>
  59. <geometry>
  60. <cylinder length="0.05" radius="0.075"/>
  61. </geometry>
  62. <origin rpy="0 0 0" xyz="0 0 0"/>
  63. </collision>
  64. <inertial>
  65. <mass value="0.2"/>
  66. <inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
  67. </inertial>
  68. </link>
  69. <link name="link_21_cyl">
  70. <visual>
  71. <geometry>
  72. <cylinder length="0.05" radius="0.075"/>
  73. </geometry>
  74. <origin rpy="0 0 0" xyz="0 0 0"/>
  75. <material name="white"/>
  76. </visual>
  77. <collision>
  78. <geometry>
  79. <cylinder length="0.05" radius="0.075"/>
  80. </geometry>
  81. <origin rpy="0 0 0" xyz="0 0 0"/>
  82. </collision>
  83. <inertial>
  84. <mass value="0.2"/>
  85. <inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
  86. </inertial>
  87. </link>
  88. <link name="link_23_cyl">
  89. <visual>
  90. <geometry>
  91. <cylinder length="0.05" radius="0.075"/>
  92. </geometry>
  93. <origin rpy="0 0 0" xyz="0 0 0"/>
  94. <material name="white"/>
  95. </visual>
  96. <collision>
  97. <geometry>
  98. <cylinder length="0.05" radius="0.075"/>
  99. </geometry>
  100. <origin rpy="0 0 0" xyz="0 0 0"/>
  101. </collision>
  102. <inertial>
  103. <mass value="0.2"/>
  104. <inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
  105. </inertial>
  106. </link>
  107. <link name="link_1">
  108. <visual>
  109. <geometry>
  110. <box size="1.0 0.1 0.05"/>
  111. </geometry>
  112. <origin rpy="0 0 0" xyz="0.5 0 0"/>
  113. <material name="blue"/>
  114. </visual>
  115. <collision>
  116. <geometry>
  117. <box size="1.0 0.1 0.05"/>
  118. </geometry>
  119. <origin rpy="0 0 0" xyz="0.5 0 0"/>
  120. </collision>
  121. <inertial>
  122. <mass value="0.5"/>
  123. <inertia ixx="0.00208333333333" ixy="0.0125" ixz="0.00625" iyy="0.167083333333" iyz="0.000625" izz="0.168333333333"/>
  124. </inertial>
  125. </link>
  126. <link name="link_2">
  127. <visual>
  128. <geometry>
  129. <box size="1.0 0.1 0.05"/>
  130. </geometry>
  131. <origin rpy="0 0 0" xyz="0.5 0 0"/>
  132. <material name="white"/>
  133. </visual>
  134. <collision>
  135. <geometry>
  136. <box size="1.0 0.1 0.05"/>
  137. </geometry>
  138. <origin rpy="0 0 0" xyz="0.5 0 0"/>
  139. </collision>
  140. <inertial>
  141. <mass value="0.5"/>
  142. <inertia ixx="0.00208333333333" ixy="0.0125" ixz="0.00625" iyy="0.167083333333" iyz="0.000625" izz="0.168333333333"/>
  143. </inertial>
  144. </link>
  145. <joint name="link_01" type="fixed">
  146. <origin rpy="0 0 0" xyz="0 0 0"/>
  147. <parent link="link_01_cyl"/>
  148. <child link="link_1"/>
  149. </joint>
  150. <joint name="link_12" type="fixed">
  151. <origin rpy="0 0 0" xyz="1.0 0 0"/>
  152. <parent link="link_1"/>
  153. <child link="link_12_cyl"/>
  154. </joint>
  155. <joint name="link_21" type="fixed">
  156. <origin rpy="0 0 0" xyz="0 0 0"/>
  157. <parent link="link_21_cyl"/>
  158. <child link="link_2"/>
  159. </joint>
  160. <joint name="link_23" type="fixed">
  161. <origin rpy="0 0 0" xyz="1.0 0 0"/>
  162. <parent link="link_2"/>
  163. <child link="link_23_cyl"/>
  164. </joint>
  165. <joint name="joint_1" type="revolute">
  166. <axis xyz="0 0 1"/>
  167. <limit effort="10000" lower="-3" upper="+3" velocity="5"/>
  168. <dynamics damping="0" friction="0"/>
  169. <origin rpy="0 0 0" xyz="0 0 0.075"/>
  170. <parent link="base_link"/>
  171. <child link="link_01_cyl"/>
  172. </joint>
  173. <joint name="joint_2" type="revolute">
  174. <axis xyz="0 0 1"/>
  175. <limit effort="10000" lower="-3" upper="+3" velocity="5"/>
  176. <dynamics damping="0" friction="0"/>
  177. <origin rpy="0 0 0" xyz="0.0 0. 0.05"/>
  178. <parent link="link_12_cyl"/>
  179. <child link="link_21_cyl"/>
  180. </joint>
  181. </robot>