urdfbot_simple.urdf 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329
  1. <?xml version="1.0"?>
  2. <robot name="urdfbot" xmlns:xacro="http://www.ros.org/wiki/xacro">
  3. <!-- Definirea bazei si suportilor -->
  4. <link name="base_link">
  5. <visual>
  6. <geometry>
  7. <mesh filename="package://urdfbot_description/meshes/Corp_hexapod.stl" scale="0.01 0.01 0.01"/>
  8. </geometry>
  9. </visual>
  10. <visual>
  11. <geometry>
  12. <mesh filename="package://urdfbot_description/meshes/suport_servo_base1.stl" scale="0.01 0.01 0.01"/>
  13. </geometry>
  14. </visual>
  15. <visual>
  16. <geometry>
  17. <mesh filename="package://urdfbot_description/meshes/suport_servo_base2.stl" scale="0.01 0.01 0.01"/>
  18. </geometry>
  19. </visual>
  20. <visual>
  21. <geometry>
  22. <mesh filename="package://urdfbot_description/meshes/suport_servo_base3.stl" scale="0.01 0.01 0.01"/>
  23. </geometry>
  24. </visual>
  25. <visual>
  26. <geometry>
  27. <mesh filename="package://urdfbot_description/meshes/suport_servo_base4.stl" scale="0.01 0.01 0.01"/>
  28. </geometry>
  29. </visual>
  30. <visual>
  31. <geometry>
  32. <mesh filename="package://urdfbot_description/meshes/suport_servo_base5.stl" scale="0.01 0.01 0.01"/>
  33. </geometry>
  34. </visual>
  35. </link>
  36. <!-- Definirea servomotoarelor montate la unghiuri -->
  37. <joint name="base_to_servo1" type="fixed">
  38. <origin xyz="0.675 0.525 0.34" rpy="4.71 4.71 0.739"/> <!-- -->
  39. <parent link="base_link"/>
  40. <child link="servo1_link"/>
  41. </joint>
  42. <link name="servo1_link">
  43. <visual>
  44. <geometry>
  45. <mesh filename="package://urdfbot_description/meshes/Servo_p_1.stl" scale="0.01 0.01 0.01"/>
  46. </geometry>
  47. </visual>
  48. </link>
  49. <joint name="base_to_servo2" type="fixed">
  50. <origin xyz="0.675 -0.525 0.34" rpy="4.71 4.71 5.55"/> <!-- -->
  51. <parent link="base_link"/>
  52. <child link="servo2_link"/>
  53. </joint>
  54. <link name="servo2_link">
  55. <visual>
  56. <geometry>
  57. <mesh filename="package://urdfbot_description/meshes/Servo_p_2.stl" scale="0.01 0.01 0.01"/>
  58. </geometry>
  59. </visual>
  60. </link>
  61. <joint name="base_to_servo3" type="fixed">
  62. <origin xyz="-0.675 -0.525 0.34" rpy="4.71 4.71 -8.69"/> <!-- -->
  63. <parent link="base_link"/>
  64. <child link="servo3_link"/>
  65. </joint>
  66. <link name="servo3_link">
  67. <visual>
  68. <geometry>
  69. <mesh filename="package://urdfbot_description/meshes/Servo_p_3.stl" scale="0.01 0.01 0.01"/>
  70. </geometry>
  71. </visual>
  72. </link>
  73. <joint name="base_to_servo4" type="fixed">
  74. <origin xyz="-0.675 0.525 0.34" rpy="4.71 4.71 -10.16"/> <!-- -->
  75. <parent link="base_link"/>
  76. <child link="servo4_link"/>
  77. </joint>
  78. <link name="servo4_link">
  79. <visual>
  80. <geometry>
  81. <mesh filename="package://urdfbot_description/meshes/Servo_p_4.stl" scale="0.01 0.01 0.01"/>
  82. </geometry>
  83. </visual>
  84. </link>
  85. <joint name="base_to_servo5" type="fixed">
  86. <origin xyz="0.1 0.75 0.34" rpy="4.71 4.71 1.565"/> <!-- -->
  87. <parent link="base_link"/>
  88. <child link="servo5_link"/>
  89. </joint>
  90. <link name="servo5_link">
  91. <visual>
  92. <geometry>
  93. <mesh filename="package://urdfbot_description/meshes/Servo_p_5.stl" scale="0.01 0.01 0.01"/>
  94. </geometry>
  95. </visual>
  96. </link>
  97. <joint name="base_to_servo6" type="fixed">
  98. <origin xyz="0.1 -0.75 0.34" rpy="4.71 4.71 4.71"/> <!-- -->
  99. <parent link="base_link"/>
  100. <child link="servo6_link"/>
  101. </joint>
  102. <link name="servo6_link">
  103. <visual>
  104. <geometry>
  105. <mesh filename="package://urdfbot_description/meshes/Servo_p_6.stl" scale="0.01 0.01 0.01"/>
  106. </geometry>
  107. </visual>
  108. </link>
  109. <!-- Bratele de baza + link uri adiacente pentru axurile motoarelor-->
  110. <joint name="brat1_to_servo1" type="revolute">
  111. <origin xyz="0 0 0" rpy="0 1.57 0"/> <!-- -->
  112. <parent link="servo1_base_link"/>
  113. <child link="brat1_link"/>
  114. <axis xyz="0 0 1"/>
  115. <limit lower="0" upper="1.57" effort="1.0" velocity="1.0"/>
  116. </joint>
  117. <!-- New Link: servo1_base_link -->
  118. <link name="servo1_base_link">
  119. <visual>
  120. <origin xyz="0 0.5 0" rpy="0 0 0"/>
  121. <geometry>
  122. <cylinder radius="0.01" length="0.02"/> <!-- A small cylinder for visualization -->
  123. </geometry>
  124. <material name="blue">
  125. <color rgba="0 0 1 1"/> <!-- Optional: Blue color -->
  126. </material>
  127. </visual>
  128. </link>
  129. <link name="brat1_link">
  130. <visual>
  131. <origin xyz = "0.095 -0.755 -0.325" rpy = "0 0 3.14159"/>
  132. <geometry>
  133. <mesh filename="package://urdfbot_description/meshes/Brat_p_1.stl" scale="0.01 0.01 0.01"/>
  134. </geometry>
  135. </visual>
  136. </link>
  137. <joint name="brat2_to_servo2" type="revolute">
  138. <origin xyz="0 0 0" rpy="0 1.57 0"/> <!-- -->
  139. <parent link="servo2_link"/>
  140. <child link="brat2_link"/>
  141. <axis xyz="0 0 1"/>
  142. <limit lower="0" upper="1.57" effort="1.0" velocity="1.0"/>
  143. </joint>
  144. <link name="brat2_link">
  145. <visual>
  146. <origin xyz = "-0.095 -0.755 -0.325" rpy = "0 0 3.14159"/>
  147. <geometry>
  148. <mesh filename="package://urdfbot_description/meshes/Brat_p_2.stl" scale="0.01 0.01 0.01"/>
  149. </geometry>
  150. </visual>
  151. </link>
  152. <joint name="brat3_to_servo3" type="revolute">
  153. <origin xyz="0 0 0" rpy="0 1.57 0"/> <!-- -->
  154. <parent link="servo3_link"/>
  155. <child link="brat3_link"/>
  156. <axis xyz="0 0 1"/>
  157. <limit lower="0" upper="1.57" effort="1.0" velocity="1.0"/>
  158. </joint>
  159. <link name="brat3_link">
  160. <visual>
  161. <origin xyz = "0.095 -0.755 -0.325" rpy = "0 0 3.14159"/>
  162. <geometry>
  163. <mesh filename="package://urdfbot_description/meshes/Brat_p_3.stl" scale="0.01 0.01 0.01"/>
  164. </geometry>
  165. </visual>
  166. </link>
  167. <joint name="brat4_to_servo4" type="revolute">
  168. <origin xyz="0 0 0" rpy="0 1.57 0"/> <!-- -->
  169. <parent link="servo4_link"/>
  170. <child link="brat4_link"/>
  171. <axis xyz="0 0 1"/>
  172. <limit lower="0" upper="1.57" effort="1.0" velocity="1.0"/>
  173. </joint>
  174. <link name="brat4_link">
  175. <visual>
  176. <origin xyz = "-0.095 -0.755 -0.325" rpy = "0 0 3.14159"/>
  177. <geometry>
  178. <mesh filename="package://urdfbot_description/meshes/Brat_p_4.stl" scale="0.01 0.01 0.01"/>
  179. </geometry>
  180. </visual>
  181. </link>
  182. <joint name="brat5_to_servo5" type="revolute">
  183. <origin xyz="0 0 0" rpy="0 1.57 0"/> <!-- -->
  184. <parent link="servo5_link"/>
  185. <child link="brat5_link"/>
  186. <axis xyz="0 0 1"/>
  187. <limit lower="0" upper="1.57" effort="1.0" velocity="1.0"/>
  188. </joint>
  189. <link name="brat5_link">
  190. <visual>
  191. <origin xyz = "-0.1 -0.755 -0.325" rpy = "0 0 3.14159"/>
  192. <geometry>
  193. <mesh filename="package://urdfbot_description/meshes/Brat_p_5.stl" scale="0.01 0.01 0.01"/>
  194. </geometry>
  195. </visual>
  196. </link>
  197. _
  198. <joint name="brat6_to_servo6" type="revolute">
  199. <origin xyz="0 0 0" rpy="0 1.57 0"/> <!-- -->
  200. <parent link="servo6_link"/>
  201. <child link="brat6_link"/>
  202. <axis xyz="0 0 1"/>
  203. <limit lower="0" upper="1.57" effort="1.0" velocity="1.0"/>
  204. </joint>
  205. <link name="brat6_link">
  206. <visual>
  207. <origin xyz = "0.1 -0.755 -0.325" rpy = "0 0 3.14159"/>
  208. <geometry>
  209. <mesh filename="package://urdfbot_description/meshes/Brat_p_6.stl" scale="0.01 0.01 0.01"/>
  210. </geometry>
  211. </visual>
  212. </link>
  213. <!-- Capace brate1 -->
  214. <joint name="capacbrat1_to_brat1" type="fixed">
  215. <origin xyz="0 0 0" rpy="0 0 0"/> <!-- -->
  216. <parent link="brat1_link"/>
  217. <child link="capacbrat1_link"/>
  218. <axis xyz="0 0 1"/>
  219. <limit lower="0" upper="1.57" effort="1.0" velocity="1.0"/>
  220. </joint>
  221. <link name="capacbrat1_link">
  222. <visual>
  223. <origin xyz = "0.1 -0.755 -0.325" rpy = "0 0 3.14159"/>
  224. <geometry>
  225. <mesh filename="package://urdfbot_description/meshes/capacBrat_p_1.stl" scale="0.01 0.01 0.01"/>
  226. </geometry>
  227. </visual>
  228. </link>
  229. <joint name="capacbrat2_to_brat2" type="fixed">
  230. <origin xyz="0 0 0" rpy="0 0 0"/> <!-- -->
  231. <parent link="brat2_link"/>
  232. <child link="capacbrat2_link"/>
  233. <axis xyz="0 0 1"/>
  234. <limit lower="0" upper="1.57" effort="1.0" velocity="1.0"/>
  235. </joint>
  236. <link name="capacbrat2_link">
  237. <visual>
  238. <origin xyz = "-0.095 -0.755 -0.325" rpy = "0 0 3.14159"/>
  239. <geometry>
  240. <mesh filename="package://urdfbot_description/meshes/capacBrat_p_2.stl" scale="0.01 0.01 0.01"/>
  241. </geometry>
  242. </visual>
  243. </link>
  244. <joint name="capacbrat3_to_brat3" type="fixed">
  245. <origin xyz="0 0 0" rpy="0 0 0"/> <!-- -->
  246. <parent link="brat3_link"/>
  247. <child link="capacbrat3_link"/>
  248. <axis xyz="0 0 1"/>
  249. <limit lower="0" upper="1.57" effort="1.0" velocity="1.0"/>
  250. </joint>
  251. <link name="capacbrat3_link">
  252. <visual>
  253. <origin xyz = "0.095 -0.755 -0.325" rpy = "0 0 3.14159"/>
  254. <geometry>
  255. <mesh filename="package://urdfbot_description/meshes/capacBrat_p_3.stl" scale="0.01 0.01 0.01"/>
  256. </geometry>
  257. </visual>
  258. </link>
  259. <joint name="capacbrat4_to_brat4" type="fixed">
  260. <origin xyz="0 0 0" rpy="0 0 0"/> <!-- -->
  261. <parent link="brat4_link"/>
  262. <child link="capacbrat4_link"/>
  263. <axis xyz="0 0 1"/>
  264. <limit lower="0" upper="1.57" effort="1.0" velocity="1.0"/>
  265. </joint>
  266. <link name="capacbrat4_link">
  267. <visual>
  268. <origin xyz = "-0.095 -0.755 -0.325" rpy = "0 0 3.14159"/>
  269. <geometry>
  270. <mesh filename="package://urdfbot_description/meshes/capacBrat_p_4.stl" scale="0.01 0.01 0.01"/>
  271. </geometry>
  272. </visual>
  273. </link>
  274. <joint name="capacbrat5_to_brat5" type="fixed">
  275. <origin xyz="0 0 0" rpy="0 0 0"/> <!-- -->
  276. <parent link="brat5_link"/>
  277. <child link="capacbrat5_link"/>
  278. <axis xyz="0 0 1"/>
  279. <limit lower="0" upper="1.57" effort="1.0" velocity="1.0"/>
  280. </joint>
  281. <link name="capacbrat5_link">
  282. <visual>
  283. <origin xyz = "-0.1 -0.755 -0.325" rpy = "0 0 3.14159"/>
  284. <geometry>
  285. <mesh filename="package://urdfbot_description/meshes/capacBrat_p_5.stl" scale="0.01 0.01 0.01"/>
  286. </geometry>
  287. </visual>
  288. </link>
  289. <joint name="capacbrat6_to_brat6" type="fixed">
  290. <origin xyz="0 0 0" rpy="0 0 0"/> <!-- -->
  291. <parent link="brat6_link"/>
  292. <child link="capacbrat6_link"/>
  293. <axis xyz="0 0 1"/>
  294. <limit lower="0" upper="1.57" effort="1.0" velocity="1.0"/>
  295. </joint>
  296. <link name="capacbrat6_link">
  297. <visual>
  298. <origin xyz = "0.1 -0.755 -0.325" rpy = "0 0 3.14159"/>
  299. <geometry>
  300. <mesh filename="package://urdfbot_description/meshes/capacBrat_p_6.stl" scale="0.01 0.01 0.01"/>
  301. </geometry>
  302. </visual>
  303. </link>
  304. </robot>