turtlebot.xacro 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575
  1. <?xml version="1.0"?>
  2. <robot name="turtlebot" xmlns:xacro="http://ros.org/wiki/xacro">
  3. <xacro:include filename="$(find rbx1_description)/urdf/turtlebot_hardware.xacro"/>
  4. <xacro:include filename="$(find rbx1_description)/urdf/gazebo.urdf.xacro"/>
  5. <material name="Green">
  6. <color rgba="0.0 0.8 0.0 1.0"/>
  7. </material>
  8. <material name="OffWhite">
  9. <color rgba="0.8 0.8 0.8 0.9"/>
  10. </material>
  11. <property name="M_PI" value="3.14159"/>
  12. <property name="SCALE" value="0.0254"/>
  13. <property name="MESH_SCALE" value="100"/>
  14. <property name="base_x" value="0.33" />
  15. <property name="base_y" value="0.33" />
  16. <macro name="turtlebot">
  17. <!-- base_footprint is a fictitious link(frame) that is on the ground right below base_link origin, navigation stack depends on this frame -->
  18. <link name="base_footprint">
  19. <inertial>
  20. <mass value="0.0001" />
  21. <origin xyz="0 0 0" />
  22. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  23. iyy="0.0001" iyz="0.0"
  24. izz="0.0001" />
  25. </inertial>
  26. <visual>
  27. <origin xyz="0 0 0" rpy="0 0 0" />
  28. <geometry>
  29. <box size="0.001 0.001 0.001" />
  30. </geometry>
  31. <material name="Green" />
  32. </visual>
  33. <collision>
  34. <origin xyz="0 0 0.017" rpy="0 0 0" />
  35. <geometry>
  36. <box size="0.001 0.001 0.001" />
  37. </geometry>
  38. </collision>
  39. </link>
  40. <link name="base_link">
  41. <inertial>
  42. <mass value="1" />
  43. <origin xyz="0 0 0.0308" />
  44. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  45. iyy="1.0" iyz="0.0" izz="1.0" />
  46. </inertial>
  47. <visual>
  48. <origin xyz=" 0 0 0.0308" rpy="0 0 0" />
  49. <geometry>
  50. <mesh filename="package://rbx1_description/meshes/create_body.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  51. </geometry>
  52. </visual>
  53. <collision>
  54. <origin xyz="0.0 0.0 0.0308" rpy="0 0 0" />
  55. <geometry>
  56. <cylinder length="0.0611632" radius="0.16495"/>
  57. </geometry>
  58. </collision>
  59. </link>
  60. <link name="wall_sensor_link">
  61. <inertial>
  62. <mass value="0.01" />
  63. <origin xyz="0 0 0"/>
  64. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  65. iyy="1.0" iyz="0.0" izz="1.0" />
  66. </inertial>
  67. </link>
  68. <link name="left_cliff_sensor_link">
  69. <inertial>
  70. <mass value="0.01" />
  71. <origin xyz="0 0 0"/>
  72. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  73. iyy="1.0" iyz="0.0" izz="1.0" />
  74. </inertial>
  75. </link>
  76. <link name="right_cliff_sensor_link">
  77. <inertial>
  78. <mass value="0.01" />
  79. <origin xyz="0 0 0"/>
  80. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  81. iyy="1.0" iyz="0.0" izz="1.0" />
  82. </inertial>
  83. </link>
  84. <link name="leftfront_cliff_sensor_link">
  85. <inertial>
  86. <mass value="0.01" />
  87. <origin xyz="0 0 0"/>
  88. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  89. iyy="1.0" iyz="0.0" izz="1.0" />
  90. </inertial>
  91. </link>
  92. <link name="rightfront_cliff_sensor_link">
  93. <inertial>
  94. <mass value="0.01" />
  95. <origin xyz="0 0 0"/>
  96. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  97. iyy="1.0" iyz="0.0" izz="1.0" />
  98. </inertial>
  99. </link>
  100. <joint name="base_footprint_joint" type="fixed">
  101. <origin xyz="0 0 0.017" rpy="0 0 0" />
  102. <parent link="base_footprint"/>
  103. <child link="base_link" />
  104. </joint>
  105. <joint name="base_wall_sensor_joint" type="fixed">
  106. <origin xyz="0.09 -0.120 0.042" rpy="0 0 -1.0" />
  107. <parent link="base_link"/>
  108. <child link="wall_sensor_link" />
  109. </joint>
  110. <joint name="base_left_cliff_sensor_joint" type="fixed">
  111. <origin xyz="0.07 0.14 0.01" rpy="0 1.57079 0" />
  112. <parent link="base_link"/>
  113. <child link="left_cliff_sensor_link" />
  114. </joint>
  115. <joint name="base_right_cliff_sensor_joint" type="fixed">
  116. <origin xyz="0.07 -0.14 0.01" rpy="0 1.57079 0" />
  117. <parent link="base_link"/>
  118. <child link="right_cliff_sensor_link" />
  119. </joint>
  120. <joint name="base_leftfront_cliff_sensor_joint" type="fixed">
  121. <origin xyz="0.15 0.04 0.01" rpy="0 1.57079 0" />
  122. <parent link="base_link"/>
  123. <child link="leftfront_cliff_sensor_link" />
  124. </joint>
  125. <joint name="base_rightfront_cliff_sensor_joint" type="fixed">
  126. <origin xyz="0.15 -0.04 0.01" rpy="0 1.57079 0" />
  127. <parent link="base_link"/>
  128. <child link="rightfront_cliff_sensor_link" />
  129. </joint>
  130. <link name="base_l_wheel_link">
  131. <inertial>
  132. <origin xyz="0 0 0"/>
  133. <mass value="0.01" />
  134. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  135. iyy="1.0" iyz="0.0" izz="1.0" />
  136. </inertial>
  137. <visual>
  138. <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
  139. <geometry>
  140. <cylinder radius="0.033" length = "0.023"/>
  141. </geometry>
  142. </visual>
  143. <collision>
  144. <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
  145. <geometry>
  146. <cylinder radius="0.033" length = "0.023"/>
  147. </geometry>
  148. </collision>
  149. </link>
  150. <joint name="base_l_wheel_joint" type="continuous">
  151. <origin xyz="0 0.13 0.015" rpy="0 0 0"/>
  152. <parent link="base_link"/>
  153. <child link="base_l_wheel_link"/>
  154. <axis xyz="0 1 0"/>
  155. </joint>
  156. <link name="base_r_wheel_link">
  157. <inertial>
  158. <origin xyz="0 0 0"/>
  159. <mass value="0.01" />
  160. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  161. iyy="1.0" iyz="0.0" izz="1.0" />
  162. </inertial>
  163. <visual>
  164. <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
  165. <geometry>
  166. <cylinder radius="0.033" length = "0.023"/>
  167. </geometry>
  168. </visual>
  169. <collision>
  170. <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
  171. <geometry>
  172. <cylinder radius="0.033" length = "0.023"/>
  173. </geometry>
  174. </collision>
  175. </link>
  176. <joint name="base_r_wheel_joint" type="continuous">
  177. <origin xyz="0 -0.13 0.015" rpy="0 0 0"/>
  178. <parent link="base_link"/>
  179. <child link="base_r_wheel_link"/>
  180. <axis xyz="0 1 0"/>
  181. </joint>
  182. <link name="rear_wheel_link">
  183. <inertial>
  184. <origin xyz="0 0 0"/>
  185. <mass value="0.001" />
  186. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  187. iyy="1.0" iyz="0.0" izz="1.0" />
  188. </inertial>
  189. <visual>
  190. <origin xyz="0 0 0" rpy="0 1.5707 1.5707"/>
  191. <geometry>
  192. <sphere radius="0.018" />
  193. </geometry>
  194. </visual>
  195. <collision>
  196. <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
  197. <geometry>
  198. <sphere radius="0.018" />
  199. </geometry>
  200. </collision>
  201. </link>
  202. <joint name="rear_castor_joint" type="fixed">
  203. <origin xyz="-0.13 0 0.0" rpy="0 0 0"/>
  204. <parent link="base_link"/>
  205. <child link="rear_wheel_link"/>
  206. <axis xyz="0 1 0"/>
  207. </joint>
  208. <link name="front_wheel_link">
  209. <inertial>
  210. <origin xyz="0 0 0" />
  211. <mass value="0.01" />
  212. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  213. iyy="1.0" iyz="0.0" izz="1.0" />
  214. </inertial>
  215. <visual>
  216. <origin xyz="0 0 0" rpy="0 1.5707 1.5707"/>
  217. <geometry>
  218. <sphere radius="0.018" />
  219. </geometry>
  220. </visual>
  221. <collision>
  222. <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
  223. <geometry>
  224. <sphere radius="0.018" />
  225. </geometry>
  226. </collision>
  227. </link>
  228. <joint name="front_castor_joint" type="fixed">
  229. <origin xyz="0.13 0 0.0" rpy="0 0 0"/>
  230. <parent link="base_link"/>
  231. <child link="front_wheel_link"/>
  232. <axis xyz="0 1 0"/>
  233. </joint>
  234. <turtlebot_spacer parent="base_link" number="0" x_loc="-0.00254" y_loc="0.1114679" z_loc="0.062992"/>
  235. <turtlebot_spacer parent="base_link" number="1" x_loc="-0.00254" y_loc="-0.1114679" z_loc="0.062992"/>
  236. <turtlebot_spacer parent="base_link" number="2" x_loc="-0.07239" y_loc="-0.1114679" z_loc="0.062992"/>
  237. <turtlebot_spacer parent="base_link" number="3" x_loc="-0.07239" y_loc="0.1114679" z_loc="0.062992"/>
  238. <joint name="gyro_joint" type="fixed">
  239. <origin xyz="0 0 0.04" rpy="0 0 0" />
  240. <parent link="base_link" />
  241. <child link="gyro_link" />
  242. </joint>
  243. <link name="gyro_link">
  244. <visual>
  245. <geometry>
  246. <box size="0.02 0.035 0.002" />
  247. </geometry>
  248. <material name="Green" />
  249. </visual>
  250. <inertial>
  251. <mass value="0.000001" />
  252. <origin xyz="0 0 0" />
  253. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  254. iyy="0.0001" iyz="0.0"
  255. izz="0.0001" />
  256. </inertial>
  257. </link>
  258. <joint name="laser_joint" type="fixed">
  259. <origin xyz="-0.065 0 0.075" rpy="0 0 0" />
  260. <parent link="base_link" />
  261. <child link="laser" />
  262. </joint>
  263. <link name="laser">
  264. <visual>
  265. <geometry>
  266. <box size="0.02 0.035 0.002" />
  267. </geometry>
  268. <material name="Green" />
  269. </visual>
  270. <inertial>
  271. <mass value="0.000001" />
  272. <origin xyz="0 0 0" />
  273. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  274. iyy="0.0001" iyz="0.0"
  275. izz="0.0001" />
  276. </inertial>
  277. </link>
  278. <joint name="plate_0_joint" type="fixed">
  279. <origin xyz="-0.04334 0 0.06775704" rpy="0 0 0" />
  280. <parent link="base_link"/>
  281. <child link="plate_0_link" />
  282. </joint>
  283. <link name="plate_0_link">
  284. <inertial>
  285. <mass value="0.01" />
  286. <origin xyz="0 0 0" />
  287. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  288. iyy="1.0" iyz="0.0"
  289. izz="1.0" />
  290. </inertial>
  291. <visual>
  292. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  293. <geometry>
  294. <mesh filename="package://rbx1_description/meshes/plate_0_logo.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  295. </geometry>
  296. </visual>
  297. <collision>
  298. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  299. <geometry>
  300. <box size="0.233502 0.314845 0.006401"/>
  301. </geometry>
  302. </collision>
  303. </link>
  304. <turtlebot_standoff_2in parent="base_link" number="0" x_loc="0.0676402" y_loc="0.1314196" z_loc="0.0709803"/>
  305. <turtlebot_standoff_2in parent="base_link" number="1" x_loc="0.0676402" y_loc="-0.1314196" z_loc="0.0709803"/>
  306. <turtlebot_standoff_2in parent="base_link" number="2" x_loc="-0.052832" y_loc="-0.1314196" z_loc="0.0709803"/>
  307. <turtlebot_standoff_2in parent="base_link" number="3" x_loc="-0.052832" y_loc="0.1314196" z_loc="0.0709803"/>
  308. <joint name="plate_1_joint" type="fixed">
  309. <origin xyz="0.04068 0 0.05715" rpy="0 0 0" />
  310. <parent link="plate_0_link"/>
  311. <child link="plate_1_link" />
  312. </joint>
  313. <link name="plate_1_link">
  314. <inertial>
  315. <mass value="0.1" />
  316. <origin xyz="0 0 0" />
  317. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  318. iyy="1.0" iyz="0.0"
  319. izz="1.0" />
  320. </inertial>
  321. <visual>
  322. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  323. <geometry>
  324. <mesh filename="package://rbx1_description/meshes/plate_1_logo.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  325. </geometry>
  326. </visual>
  327. <collision>
  328. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  329. <geometry>
  330. <box size="0.314856 0.314856 0.006401"/>
  331. </geometry>
  332. </collision>
  333. </link>
  334. <turtlebot_standoff_2in parent="standoff_2in_0_link" number="4" x_loc="0" y_loc="0" z_loc="0.05715"/>
  335. <turtlebot_standoff_2in parent="standoff_2in_1_link" number="5" x_loc="0" y_loc="0" z_loc="0.05715"/>
  336. <turtlebot_standoff_2in parent="standoff_2in_2_link" number="6" x_loc="0" y_loc="0" z_loc="0.05715"/>
  337. <turtlebot_standoff_2in parent="standoff_2in_3_link" number="7" x_loc="0" y_loc="0" z_loc="0.05715"/>
  338. <joint name="plate_2_joint" type="fixed">
  339. <origin xyz="0 0 0.0572008" rpy="0 0 0" />
  340. <parent link="plate_1_link"/>
  341. <child link="plate_2_link" />
  342. </joint>
  343. <link name="plate_2_link">
  344. <inertial>
  345. <mass value="0.01" />
  346. <origin xyz="0 0 0" />
  347. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  348. iyy="1.0" iyz="0.0"
  349. izz="1.0" />
  350. </inertial>
  351. <visual>
  352. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  353. <geometry>
  354. <mesh filename="package://rbx1_description/meshes/plate_1_logo.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  355. </geometry>
  356. </visual>
  357. <collision>
  358. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  359. <geometry>
  360. <box size="0.314856 0.314856 0.006401"/>
  361. </geometry>
  362. </collision>
  363. </link>
  364. <!--
  365. <joint name="base_kinect_joint" type="fixed">
  366. <origin xyz="${turtlebot_calib_cam_x} ${turtlebot_calib_cam_y} ${turtlebot_calib_cam_z}"
  367. rpy="${turtlebot_calib_cam_rr} ${turtlebot_calib_cam_rp} ${turtlebot_calib_cam_ry}" />
  368. <parent link="${turtlebot_kinect_frame_name}" />
  369. <child link="kinect_link" />
  370. </joint>
  371. <link name="kinect_link">
  372. <inertial>
  373. <mass value="0.00001" />
  374. <origin xyz="0 0 0" />
  375. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  376. iyy="1.0" iyz="0.0"
  377. izz="1.0" />
  378. </inertial>
  379. <visual>
  380. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  381. <geometry>
  382. <mesh filename="package://rbx1_description/meshes/kinect.dae"/>
  383. </geometry>
  384. </visual>
  385. <collision>
  386. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  387. <geometry>
  388. <box size="0.0730 .2760 0.0720"/>
  389. </geometry>
  390. </collision>
  391. </link>
  392. <joint name="kinect_depth_joint" type="fixed">
  393. <origin xyz="0 0.018 0" rpy="0 0 0" />
  394. <parent link="kinect_link" />
  395. <child link="kinect_depth_frame" />
  396. </joint>
  397. <link name="kinect_depth_frame">
  398. <inertial>
  399. <mass value="0.000001" />
  400. <origin xyz="0 0 0" />
  401. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  402. iyy="0.0001" iyz="0.0"
  403. izz="0.0001" />
  404. </inertial>
  405. </link>
  406. <joint name="kinect_depth_optical_joint" type="fixed">
  407. <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
  408. <parent link="kinect_depth_frame" />
  409. <child link="kinect_depth_optical_frame" />
  410. </joint>
  411. <link name="kinect_depth_optical_frame">
  412. <inertial>
  413. <mass value="0.000001" />
  414. <origin xyz="0 0 0" />
  415. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  416. iyy="0.0001" iyz="0.0"
  417. izz="0.0001" />
  418. </inertial>
  419. </link>
  420. <joint name="kinect_rgb_joint" type="fixed">
  421. <origin xyz="0 -0.005 0" rpy="0 0 0" />
  422. <parent link="kinect_link" />
  423. <child link="kinect_rgb_frame" />
  424. </joint>
  425. <link name="kinect_rgb_frame">
  426. <inertial>
  427. <mass value="0.000001" />
  428. <origin xyz="0 0 0" />
  429. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  430. iyy="0.0001" iyz="0.0"
  431. izz="0.0001" />
  432. </inertial>
  433. </link>
  434. <joint name="kinect_rgb_optical_joint" type="fixed">
  435. <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
  436. <parent link="kinect_rgb_frame" />
  437. <child link="kinect_rgb_optical_frame" />
  438. </joint>
  439. <link name="kinect_rgb_optical_frame">
  440. <inertial>
  441. <mass value="0.000001" />
  442. <origin xyz="0 0 0" />
  443. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  444. iyy="0.0001" iyz="0.0"
  445. izz="0.0001" />
  446. </inertial>
  447. </link>
  448. <xacro:my_cylinder name="left_eye_link" l="0.01" r="0.01" xyz="0 0 0" rpy="0 1.57 0" mass="0.001" material="Gazebo/WhiteEmissive">
  449. <xacro:grey3 />
  450. </xacro:my_cylinder>
  451. <xacro:my_cylinder name="right_eye_link" l="0.01" r="0.01" xyz="0 0 00" rpy="0 1.57 0" mass="0.001" material="Gazebo/WhiteEmissive">
  452. <xacro:grey3 />
  453. </xacro:my_cylinder>
  454. <turtlebot_standoff_kinect parent="plate_2_link" number="0" x_loc="-0.1024382" y_loc="0.098" z_loc="0.0032004"/>
  455. <turtlebot_standoff_kinect parent="plate_2_link" number="1" x_loc="-0.1024382" y_loc="-0.098" z_loc="0.0032004"/>
  456. -->
  457. <turtlebot_standoff_3in parent="standoff_2in_4_link" number="0" x_loc="0" y_loc="0" z_loc="0.05715"/>
  458. <turtlebot_standoff_3in parent="standoff_2in_5_link" number="1" x_loc="0" y_loc="0" z_loc="0.05715"/>
  459. <turtlebot_standoff_3in parent="standoff_2in_6_link" number="2" x_loc="0" y_loc="0" z_loc="0.05715"/>
  460. <turtlebot_standoff_3in parent="standoff_2in_7_link" number="3" x_loc="0" y_loc="0" z_loc="0.05715"/>
  461. <joint name="plate_3_joint" type="fixed">
  462. <origin xyz="-0.01316 0 0.08" rpy="0 0 0" />
  463. <parent link="plate_2_link"/>
  464. <child link="plate_3_link" />
  465. </joint>
  466. <link name="plate_3_link">
  467. <inertial>
  468. <mass value="0.01" />
  469. <origin xyz="0 0 0" />
  470. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  471. iyy="1.0" iyz="0.0"
  472. izz="1.0" />
  473. </inertial>
  474. <visual>
  475. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  476. <geometry>
  477. <mesh filename="package://rbx1_description/meshes/plate_2_logo.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  478. </geometry>
  479. </visual>
  480. <collision>
  481. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  482. <geometry>
  483. <box size="0.288 0.315 0.006401"/>
  484. </geometry>
  485. </collision>
  486. </link>
  487. </macro>
  488. </robot>