turtlebot_body.urdf.xacro 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454
  1. <?xml version="1.0"?>
  2. <robot name="turtlebot_body" xmlns:xacro="http://ros.org/wiki/xacro">
  3. <property name="M_PI" value="3.14159"/>
  4. <property name="MESH_SCALE" value="100"/>
  5. <!-- Macro for TurtleBot body. Including Gazebo extensions, but does not include Kinect -->
  6. <xacro:include filename="$(find rbx1_description)/urdf/gazebo.urdf.xacro"/>
  7. <property name="base_x" value="0.33" />
  8. <property name="base_y" value="0.33" />
  9. <xacro:macro name="turtlebot_body">
  10. <material name="Green">
  11. <color rgba="0.0 0.8 0.0 1.0"/>
  12. </material>
  13. <!-- base_footprint is a fictitious link(frame) that is on the ground right below base_link origin, navigation stack depends on this frame -->
  14. <link name="base_footprint">
  15. <visual>
  16. <origin xyz="0 0 0" rpy="0 0 0" />
  17. <geometry>
  18. <box size="0.001 0.001 0.001" />
  19. </geometry>
  20. <material name="Green" />
  21. </visual>
  22. <collision>
  23. <origin xyz="0 0 0.017" rpy="0 0 0" />
  24. <geometry>
  25. <box size="0.001 0.001 0.001" />
  26. </geometry>
  27. </collision>
  28. </link>
  29. <link name="base_link">
  30. <inertial>
  31. <mass value="2" />
  32. <origin xyz="0 0 0.0" />
  33. <inertia ixx="0.01" ixy="0.0" ixz="0.0"
  34. iyy="0.01" iyz="0.0" izz="0.5" />
  35. </inertial>
  36. <visual>
  37. <origin xyz=" 0 0 0.0308" rpy="0 0 0" />
  38. <geometry>
  39. <mesh filename="package://rbx1_description/meshes/create_body.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  40. </geometry>
  41. </visual>
  42. <collision>
  43. <origin xyz="0.0 0.0 0.0308" rpy="0 0 0" />
  44. <geometry>
  45. <cylinder length="0.0611632" radius="0.016495"/>
  46. </geometry>
  47. </collision>
  48. </link>
  49. <link name="wall_sensor_link">
  50. <inertial>
  51. <mass value="0.01" />
  52. <origin xyz="0 0 0"/>
  53. <inertia ixx="0.001" ixy="0.0" ixz="0.0"
  54. iyy="0.001" iyz="0.0" izz="0.001" />
  55. </inertial>
  56. </link>
  57. <link name="left_cliff_sensor_link">
  58. <inertial>
  59. <mass value="0.01" />
  60. <origin xyz="0 0 0"/>
  61. <inertia ixx="0.001" ixy="0.0" ixz="0.0"
  62. iyy="0.001" iyz="0.0" izz="0.001" />
  63. </inertial>
  64. </link>
  65. <link name="right_cliff_sensor_link">
  66. <inertial>
  67. <mass value="0.01" />
  68. <origin xyz="0 0 0"/>
  69. <inertia ixx="0.001" ixy="0.0" ixz="0.0"
  70. iyy="0.001" iyz="0.0" izz="0.001" />
  71. </inertial>
  72. </link>
  73. <link name="leftfront_cliff_sensor_link">
  74. <inertial>
  75. <mass value="0.01" />
  76. <origin xyz="0 0 0"/>
  77. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  78. iyy="0.01" iyz="0.0" izz="0.01" />
  79. </inertial>
  80. </link>
  81. <link name="rightfront_cliff_sensor_link">
  82. <inertial>
  83. <mass value="0.01" />
  84. <origin xyz="0 0 0"/>
  85. <inertia ixx="0.001" ixy="0.0" ixz="0.0"
  86. iyy="0.001" iyz="0.0" izz="0.001" />
  87. </inertial>
  88. </link>
  89. <joint name="base_footprint_joint" type="fixed">
  90. <origin xyz="0 0 0.017" rpy="0 0 0" />
  91. <parent link="base_footprint"/>
  92. <child link="base_link" />
  93. </joint>
  94. <joint name="base_wall_sensor_joint" type="fixed">
  95. <origin xyz="0.09 -0.120 0.042" rpy="0 0 -1.0" />
  96. <parent link="base_link"/>
  97. <child link="wall_sensor_link" />
  98. </joint>
  99. <joint name="base_left_cliff_sensor_joint" type="fixed">
  100. <origin xyz="0.07 0.14 0.01" rpy="0 1.57079 0" />
  101. <parent link="base_link"/>
  102. <child link="left_cliff_sensor_link" />
  103. </joint>
  104. <joint name="base_right_cliff_sensor_joint" type="fixed">
  105. <origin xyz="0.07 -0.14 0.01" rpy="0 1.57079 0" />
  106. <parent link="base_link"/>
  107. <child link="right_cliff_sensor_link" />
  108. </joint>
  109. <joint name="base_leftfront_cliff_sensor_joint" type="fixed">
  110. <origin xyz="0.15 0.04 0.01" rpy="0 1.57079 0" />
  111. <parent link="base_link"/>
  112. <child link="leftfront_cliff_sensor_link" />
  113. </joint>
  114. <joint name="base_rightfront_cliff_sensor_joint" type="fixed">
  115. <origin xyz="0.15 -0.04 0.01" rpy="0 1.57079 0" />
  116. <parent link="base_link"/>
  117. <child link="rightfront_cliff_sensor_link" />
  118. </joint>
  119. <link name="left_wheel_link">
  120. <inertial>
  121. <origin xyz="0 0 0"/>
  122. <mass value="0.01" />
  123. <inertia ixx="0.001" ixy="0.0" ixz="0.0"
  124. iyy="0.001" iyz="0.0" izz="0.001" />
  125. </inertial>
  126. <visual>
  127. <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
  128. <geometry>
  129. <cylinder radius="0.033" length = "0.023"/>
  130. </geometry>
  131. </visual>
  132. <collision>
  133. <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
  134. <geometry>
  135. <cylinder radius="0.033" length = "0.023"/>
  136. </geometry>
  137. </collision>
  138. </link>
  139. <joint name="base_l_wheel_joint" type="continuous">
  140. <origin xyz="0 0.13 0.015" rpy="0 0 0"/>
  141. <parent link="base_link"/>
  142. <child link="left_wheel_link"/>
  143. <axis xyz="0 1 0"/>
  144. </joint>
  145. <link name="right_wheel_link">
  146. <inertial>
  147. <origin xyz="0 0 0"/>
  148. <mass value="0.01" />
  149. <inertia ixx="0.001" ixy="0.0" ixz="0.0"
  150. iyy="0.001" iyz="0.0" izz="0.001" />
  151. </inertial>
  152. <visual>
  153. <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
  154. <geometry>
  155. <cylinder radius="0.033" length = "0.023"/>
  156. </geometry>
  157. </visual>
  158. <collision>
  159. <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
  160. <geometry>
  161. <cylinder radius="0.033" length = "0.023"/>
  162. </geometry>
  163. </collision>
  164. </link>
  165. <joint name="base_r_wheel_joint" type="continuous">
  166. <origin xyz="0 -0.13 0.015" rpy="0 0 0"/>
  167. <parent link="base_link"/>
  168. <child link="right_wheel_link"/>
  169. <axis xyz="0 1 0"/>
  170. </joint>
  171. <link name="rear_wheel_link">
  172. <inertial>
  173. <origin xyz="0 0 0"/>
  174. <mass value="0.001" />
  175. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  176. iyy="0.0001" iyz="0.0" izz="0.0001" />
  177. </inertial>
  178. <visual>
  179. <origin xyz="0 0 0" rpy="0 1.5707 1.5707"/>
  180. <geometry>
  181. <sphere radius="0.015" />
  182. </geometry>
  183. </visual>
  184. <collision>
  185. <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
  186. <geometry>
  187. <sphere radius="0.015" />
  188. </geometry>
  189. </collision>
  190. </link>
  191. <!-- fixed because there's no transmission -->
  192. <joint name="rear_castor_joint" type="fixed">
  193. <origin xyz="-0.13 0 0.0" rpy="0 0 0"/>
  194. <parent link="base_link"/>
  195. <child link="rear_wheel_link"/>
  196. <axis xyz="0 1 0"/>
  197. </joint>
  198. <link name="front_wheel_link">
  199. <inertial>
  200. <origin xyz="0 0 0" />
  201. <mass value="0.01" />
  202. <inertia ixx="0.001" ixy="0.0" ixz="0.0"
  203. iyy="0.001" iyz="0.0" izz="0.001" />
  204. </inertial>
  205. <visual>
  206. <origin xyz="0 0 0" rpy="0 1.5707 1.5707"/>
  207. <geometry>
  208. <sphere radius="0.018" />
  209. </geometry>
  210. </visual>
  211. <collision>
  212. <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
  213. <geometry>
  214. <sphere radius="0.018" />
  215. </geometry>
  216. </collision>
  217. </link>
  218. <!-- fixed because there's no transmission -->
  219. <joint name="front_castor_joint" type="fixed">
  220. <origin xyz="0.13 0 0.0" rpy="0 0 0"/>
  221. <parent link="base_link"/>
  222. <child link="front_wheel_link"/>
  223. <axis xyz="0 1 0"/>
  224. </joint>
  225. <turtlebot_spacer parent="base_link" number="0" x_loc="-0.00254" y_loc="0.1114679" z_loc="0.062992"/>
  226. <turtlebot_spacer parent="base_link" number="1" x_loc="-0.00254" y_loc="-0.1114679" z_loc="0.062992"/>
  227. <turtlebot_spacer parent="base_link" number="2" x_loc="-0.07239" y_loc="-0.1114679" z_loc="0.062992"/>
  228. <turtlebot_spacer parent="base_link" number="3" x_loc="-0.07239" y_loc="0.1114679" z_loc="0.062992"/>
  229. <joint name="gyro_joint" type="fixed">
  230. <axis xyz="0 1 0" />
  231. <origin xyz="0 0 0.04" rpy="0 0 0" />
  232. <parent link="base_link"/>
  233. <child link="gyro_link"/>
  234. </joint>
  235. <link name="gyro_link">
  236. <inertial>
  237. <mass value="0.001" />
  238. <origin xyz="0 0 0" rpy="0 0 0" />
  239. <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001" />
  240. </inertial>
  241. </link>
  242. <joint name="laser_joint" type="fixed">
  243. <origin xyz="-0.065 0 0.075" rpy="0 0 0" />
  244. <parent link="base_link" />
  245. <child link="laser" />
  246. </joint>
  247. <link name="laser">
  248. <visual>
  249. <geometry>
  250. <box size="0.02 0.035 0.002" />
  251. </geometry>
  252. <material name="Green" />
  253. </visual>
  254. <inertial>
  255. <mass value="0.001" />
  256. <origin xyz="0 0 0" />
  257. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  258. iyy="0.0001" iyz="0.0"
  259. izz="0.0001" />
  260. </inertial>
  261. </link>
  262. <joint name="plate_0_joint" type="fixed">
  263. <origin xyz="-0.04334 0 0.06775704" rpy="0 0 0" />
  264. <parent link="base_link"/>
  265. <child link="plate_0_link" />
  266. </joint>
  267. <link name="plate_0_link">
  268. <inertial>
  269. <mass value="0.01" />
  270. <origin xyz="0 0 0" />
  271. <inertia ixx="0.01" ixy="0.0" ixz="0.0"
  272. iyy="0.01" iyz="0.0"
  273. izz="0.01" />
  274. </inertial>
  275. <visual>
  276. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  277. <geometry>
  278. <mesh filename="package://rbx1_description/meshes/plate_0_logo.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  279. </geometry>
  280. </visual>
  281. <collision>
  282. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  283. <geometry>
  284. <box size="0.233502 0.314845 0.006401"/>
  285. </geometry>
  286. </collision>
  287. </link>
  288. <turtlebot_standoff_2in parent="base_link" number="0" x_loc="0.0676402" y_loc="0.1314196" z_loc="0.0709803"/>
  289. <turtlebot_standoff_2in parent="base_link" number="1" x_loc="0.0676402" y_loc="-0.1314196" z_loc="0.0709803"/>
  290. <turtlebot_standoff_2in parent="base_link" number="2" x_loc="-0.052832" y_loc="-0.1314196" z_loc="0.0709803"/>
  291. <turtlebot_standoff_2in parent="base_link" number="3" x_loc="-0.052832" y_loc="0.1314196" z_loc="0.0709803"/>
  292. <joint name="plate_1_joint" type="fixed">
  293. <origin xyz="0.04068 0 0.05715" rpy="0 0 0" />
  294. <parent link="plate_0_link"/>
  295. <child link="plate_1_link" />
  296. </joint>
  297. <link name="plate_1_link">
  298. <inertial>
  299. <mass value="0.1" />
  300. <origin xyz="0 0 0" />
  301. <inertia ixx="0.01" ixy="0.0" ixz="0.0"
  302. iyy="0.01" iyz="0.0"
  303. izz="0.01" />
  304. </inertial>
  305. <visual>
  306. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  307. <geometry>
  308. <mesh filename="package://rbx1_description/meshes/plate_1_logo.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  309. </geometry>
  310. </visual>
  311. <collision>
  312. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  313. <geometry>
  314. <box size="0.314856 0.314856 0.006401"/>
  315. </geometry>
  316. </collision>
  317. </link>
  318. <turtlebot_standoff_2in parent="standoff_2in_0_link" number="4" x_loc="0" y_loc="0" z_loc="0.05715"/>
  319. <turtlebot_standoff_2in parent="standoff_2in_1_link" number="5" x_loc="0" y_loc="0" z_loc="0.05715"/>
  320. <turtlebot_standoff_2in parent="standoff_2in_2_link" number="6" x_loc="0" y_loc="0" z_loc="0.05715"/>
  321. <turtlebot_standoff_2in parent="standoff_2in_3_link" number="7" x_loc="0" y_loc="0" z_loc="0.05715"/>
  322. <joint name="plate_2_joint" type="fixed">
  323. <origin xyz="0 0 0.0572008" rpy="0 0 0" />
  324. <parent link="plate_1_link"/>
  325. <child link="plate_2_link" />
  326. </joint>
  327. <link name="plate_2_link">
  328. <inertial>
  329. <mass value="0.01" />
  330. <origin xyz="0 0 0" />
  331. <inertia ixx="0.001" ixy="0.0" ixz="0.0"
  332. iyy="0.001" iyz="0.0"
  333. izz="0.001" />
  334. </inertial>
  335. <visual>
  336. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  337. <geometry>
  338. <mesh filename="package://rbx1_description/meshes/plate_1_logo.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  339. </geometry>
  340. </visual>
  341. <collision>
  342. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  343. <geometry>
  344. <box size="0.314856 0.314856 0.006401"/>
  345. </geometry>
  346. </collision>
  347. </link>
  348. <turtlebot_standoff_kinect parent="plate_2_link" number="0" x_loc="-0.1024382" y_loc="0.098" z_loc="0.0032004"/>
  349. <turtlebot_standoff_kinect parent="plate_2_link" number="1" x_loc="-0.1024382" y_loc="-0.098" z_loc="0.0032004"/>
  350. <turtlebot_standoff_8in parent="standoff_2in_4_link" number="0" x_loc="0" y_loc="0" z_loc="0.05715"/>
  351. <turtlebot_standoff_8in parent="standoff_2in_5_link" number="1" x_loc="0" y_loc="0" z_loc="0.05715"/>
  352. <turtlebot_standoff_8in parent="standoff_2in_6_link" number="2" x_loc="0" y_loc="0" z_loc="0.05715"/>
  353. <turtlebot_standoff_8in parent="standoff_2in_7_link" number="3" x_loc="0" y_loc="0" z_loc="0.05715"/>
  354. <joint name="plate_3_joint" type="fixed">
  355. <origin xyz="-0.01316 0 0.2063496" rpy="0 0 0" />
  356. <parent link="plate_2_link"/>
  357. <child link="plate_3_link" />
  358. </joint>
  359. <link name="plate_3_link">
  360. <inertial>
  361. <mass value="0.01" />
  362. <origin xyz="0 0 0" />
  363. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  364. iyy="0.0001" iyz="0.0"
  365. izz="0.0001" />
  366. </inertial>
  367. <visual>
  368. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  369. <geometry>
  370. <mesh filename="package://rbx1_description/meshes/plate_2_logo.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  371. </geometry>
  372. </visual>
  373. <collision>
  374. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  375. <geometry>
  376. <box size="0.288 0.315 0.006401"/>
  377. </geometry>
  378. </collision>
  379. </link>
  380. <!-- Simulation sensors -->
  381. <turtlebot_sim_imu/>
  382. <turtlebot_sim_laser/>
  383. <turtlebot_sim_create/>
  384. <turtlebot_sim_wall_sensors/>
  385. </xacro:macro>
  386. </robot>