diff_ring.urdf 5.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198
  1. <?xml version="1.0" ?>
  2. <robot name="husky_robot" xmlns:xacro="http://ros.org/wiki/xacro">
  3. <material name="White">
  4. <color rgba="1.0 1.0 1.0 1.0"/>
  5. </material>
  6. <link name="world"/>
  7. <link name="diff_ring">
  8. <contact>
  9. <lateral_friction value="1.0"/>
  10. <rolling_friction value="0.0"/>
  11. <stiffness value="30000"/>
  12. <damping value="1000"/>
  13. </contact>
  14. <inertial>
  15. <mass value="2.637"/>
  16. <origin xyz="0 0 0"/>
  17. <inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
  18. </inertial>
  19. <visual>
  20. <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
  21. <geometry>
  22. <mesh scale="0.001 0.001 0.001" filename="differential/diff_ring.stl"/>
  23. </geometry>
  24. <material name="DarkGrey"/>
  25. </visual>
  26. <visual>
  27. <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
  28. <geometry>
  29. <mesh scale="0.001 0.001 0.001" filename="differential/diff_carrier.stl"/>
  30. </geometry>
  31. <material name="DarkGrey"/>
  32. </visual>
  33. <collision>
  34. <origin rpy="1.570795 0 0" xyz="0 0.025 0"/>
  35. <geometry>
  36. <cylinder length="0.01" radius="0.05"/>
  37. </geometry>
  38. </collision>
  39. </link>
  40. <joint name="diff_ring_world" type="continuous">
  41. <parent link="world"/>
  42. <child link="diff_ring"/>
  43. <origin rpy="0 0 0" xyz="0.256 0.2854 0.03282"/>
  44. <axis rpy="0 0 0" xyz="0 1 0"/>
  45. </joint>
  46. <link name="diff_spiderA">
  47. <contact>
  48. <lateral_friction value="1.0"/>
  49. <rolling_friction value="0.0"/>
  50. <stiffness value="30000"/>
  51. <damping value="1000"/>
  52. </contact>
  53. <inertial>
  54. <mass value="2.637"/>
  55. <origin xyz="0 0 0"/>
  56. <inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
  57. </inertial>
  58. <visual>
  59. <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
  60. <geometry>
  61. <mesh scale="0.001 0.001 0.001" filename="differential/diff_spider.stl"/>
  62. </geometry>
  63. <material name="DarkGrey"/>
  64. </visual>
  65. <collision>
  66. <origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
  67. <geometry>
  68. <cylinder length="0.01" radius="0.015"/>
  69. </geometry>
  70. </collision>
  71. </link>
  72. <joint name="diff_spiderA_ring" type="continuous">
  73. <parent link="diff_ring"/>
  74. <child link="diff_spiderA"/>
  75. <origin rpy="0 0 1.570795" xyz="0.0 0.0 0.0"/>
  76. <axis rpy="0 0 0" xyz="0 1 0"/>
  77. </joint>
  78. <link name="diff_spiderB">
  79. <contact>
  80. <lateral_friction value="1.0"/>
  81. <rolling_friction value="0.0"/>
  82. <stiffness value="30000"/>
  83. <damping value="1000"/>
  84. </contact>
  85. <inertial>
  86. <mass value="2.637"/>
  87. <origin xyz="0 0 0"/>
  88. <inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
  89. </inertial>
  90. <visual>
  91. <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
  92. <geometry>
  93. <mesh scale="0.001 0.001 0.001" filename="differential/diff_spider.stl"/>
  94. </geometry>
  95. <material name="DarkGrey"/>
  96. </visual>
  97. <collision>
  98. <origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
  99. <geometry>
  100. <cylinder length="0.01" radius="0.015"/>
  101. </geometry>
  102. </collision>
  103. </link>
  104. <joint name="diff_spiderB_ring" type="continuous">
  105. <parent link="diff_ring"/>
  106. <child link="diff_spiderB"/>
  107. <origin rpy="0 0 -1.570795" xyz="0.0 0.0 0.0"/>
  108. <axis rpy="0 0 0" xyz="0 1 0"/>
  109. </joint>
  110. <link name="diff_sideA">
  111. <contact>
  112. <lateral_friction value="1.0"/>
  113. <rolling_friction value="0.0"/>
  114. <stiffness value="30000"/>
  115. <damping value="1000"/>
  116. </contact>
  117. <inertial>
  118. <mass value="2.637"/>
  119. <origin xyz="0 0 0"/>
  120. <inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
  121. </inertial>
  122. <visual>
  123. <origin rpy="1.570795 0 0" xyz="0 0 0"/>
  124. <geometry>
  125. <mesh scale="0.001 0.001 0.001" filename="differential/diff_side.stl"/>
  126. </geometry>
  127. <material name="DarkGrey"/>
  128. </visual>
  129. <collision>
  130. <origin rpy="1.570795 0 0" xyz="0 0.01 0"/>
  131. <geometry>
  132. <cylinder length="0.01" radius="0.015"/>
  133. </geometry>
  134. </collision>
  135. </link>
  136. <joint name="diff_sideA_ring" type="continuous">
  137. <parent link="diff_ring"/>
  138. <child link="diff_sideA"/>
  139. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  140. <axis rpy="0 0 0" xyz="0 1 0"/>
  141. </joint>
  142. <link name="diff_sideB">
  143. <contact>
  144. <lateral_friction value="1.0"/>
  145. <rolling_friction value="0.0"/>
  146. <stiffness value="30000"/>
  147. <damping value="1000"/>
  148. </contact>
  149. <inertial>
  150. <mass value="2.637"/>
  151. <origin xyz="0 0 0"/>
  152. <inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
  153. </inertial>
  154. <visual>
  155. <origin rpy="-1.570795 0 0" xyz="0 0 0"/>
  156. <geometry>
  157. <mesh scale="0.001 0.001 0.001" filename="differential/diff_side.stl"/>
  158. </geometry>
  159. <material name="DarkGrey"/>
  160. </visual>
  161. <collision>
  162. <origin rpy="-1.570795 0 0" xyz="0 -0.01 0"/>
  163. <geometry>
  164. <cylinder length="0.01" radius="0.015"/>
  165. </geometry>
  166. </collision>
  167. </link>
  168. <joint name="diff_sideB_ring" type="continuous">
  169. <parent link="diff_ring"/>
  170. <child link="diff_sideB"/>
  171. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  172. <axis rpy="0 0 0" xyz="0 1 0"/>
  173. </joint>
  174. </robot>