robot.urdf 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494
  1. <robot name="robot">
  2. <material name="blue">
  3. <color rgba="0.1 0.1 0.75 0.9"/>
  4. </material>
  5. <link
  6. name="base_link">
  7. <inertial>
  8. <origin
  9. xyz="-1.30824055561016E-05 0.000107844191407841 0.0577157555063256"
  10. rpy="0 0 0" />
  11. <mass
  12. value="0.715394481464921" />
  13. <inertia
  14. ixx="0.000779865515276959"
  15. ixy="1.02445392057065E-07"
  16. ixz="6.95832095402999E-08"
  17. iyy="0.000862321943367308"
  18. iyz="2.63518497731006E-08"
  19. izz="0.00160121250638599" />
  20. </inertial>
  21. <visual>
  22. <origin
  23. xyz="0 0 0"
  24. rpy="0 0 0" />
  25. <geometry>
  26. <mesh
  27. filename="package://robot_description/meshes/base_link.STL" />
  28. </geometry>
  29. <material
  30. name="">
  31. <color
  32. rgba="0.941176470588235 0.941176470588235 0.941176470588235 1" />
  33. </material>
  34. </visual>
  35. <collision>
  36. <origin
  37. xyz="0 0 0"
  38. rpy="0 0 0" />
  39. <geometry>
  40. <mesh
  41. filename="package://robot_description/meshes/base_link.STL" />
  42. </geometry>
  43. </collision>
  44. </link>
  45. <link
  46. name="left_wheel_link">
  47. <inertial>
  48. <origin
  49. xyz="-7.66164786097183E-18 8.40811733798796E-05 -3.46944695195361E-18"
  50. rpy="0 0 0" />
  51. <mass
  52. value="0.056636933308092" />
  53. <inertia
  54. ixx="2.5061060504477E-05"
  55. ixy="-8.26321294879238E-18"
  56. ixz="7.70223898149877E-08"
  57. iyy="4.40641001526507E-05"
  58. iyz="-1.61023780640282E-17"
  59. izz="2.52148616363739E-05" />
  60. </inertial>
  61. <visual>
  62. <origin
  63. xyz="0 0 0"
  64. rpy="0 0 0" />
  65. <geometry>
  66. <mesh
  67. filename="package://robot_description/meshes/left_wheel_link.STL" />
  68. </geometry>
  69. <material
  70. name="">
  71. <color
  72. rgba="0.792156862745098 0.972549019607843 1 1" />
  73. </material>
  74. </visual>
  75. <collision>
  76. <origin
  77. xyz="0 0 0"
  78. rpy="0 0 0" />
  79. <geometry>
  80. <mesh
  81. filename="package://robot_description/meshes/left_wheel_link.STL" />
  82. </geometry>
  83. </collision>
  84. </link>
  85. <joint
  86. name="left_wheel_joint"
  87. type="continuous">
  88. <origin
  89. xyz="0 0.087226 -0.02"
  90. rpy="0 0 0" />
  91. <parent
  92. link="base_link" />
  93. <child
  94. link="left_wheel_link" />
  95. <axis
  96. xyz="0 1 0" />
  97. </joint>
  98. <link
  99. name="right_wheel_link">
  100. <inertial>
  101. <origin
  102. xyz="-1.13392370823798E-18 -8.40811733799074E-05 -1.38777878078145E-17"
  103. rpy="0 0 0" />
  104. <mass
  105. value="0.056636933308092" />
  106. <inertia
  107. ixx="2.5061060504477E-05"
  108. ixy="-8.27358108286742E-18"
  109. ixz="-7.7022389814995E-08"
  110. iyy="4.40641001526506E-05"
  111. iyz="1.6102381956134E-17"
  112. izz="2.52148616363739E-05" />
  113. </inertial>
  114. <visual>
  115. <origin
  116. xyz="0 0 0"
  117. rpy="0 0 0" />
  118. <geometry>
  119. <mesh
  120. filename="package://robot_description/meshes/right_wheel_link.STL" />
  121. </geometry>
  122. <material
  123. name="">
  124. <color
  125. rgba="0.43921568627451 0.43921568627451 0.43921568627451 1" />
  126. </material>
  127. </visual>
  128. <collision>
  129. <origin
  130. xyz="0 0 0"
  131. rpy="0 0 0" />
  132. <geometry>
  133. <mesh
  134. filename="package://robot_description/meshes/right_wheel_link.STL" />
  135. </geometry>
  136. </collision>
  137. </link>
  138. <joint
  139. name="right_wheel_joint"
  140. type="continuous">
  141. <origin
  142. xyz="0 -0.087226 -0.02"
  143. rpy="0 0 0" />
  144. <parent
  145. link="base_link" />
  146. <child
  147. link="right_wheel_link" />
  148. <axis
  149. xyz="0 -1 0" />
  150. </joint>
  151. <link
  152. name="front_wheel_link">
  153. <inertial>
  154. <origin
  155. xyz="0.0152655251450065 0.000504489640389129 -0.0275267772713533"
  156. rpy="0 0 0" />
  157. <mass
  158. value="0.0323710595794446" />
  159. <inertia
  160. ixx="5.13858672949531E-06"
  161. ixy="-7.37337358165628E-08"
  162. ixz="2.43411911798529E-07"
  163. iyy="7.36892066003594E-06"
  164. iyz="8.05146812807082E-09"
  165. izz="5.0594631354647E-06" />
  166. </inertial>
  167. <visual>
  168. <origin
  169. xyz="0 0 0"
  170. rpy="0 0 0" />
  171. <geometry>
  172. <mesh
  173. filename="package://robot_description/meshes/front_wheel_link.STL" />
  174. </geometry>
  175. <material
  176. name="">
  177. <color
  178. rgba="1 1 1 1" />
  179. </material>
  180. </visual>
  181. <collision>
  182. <origin
  183. xyz="0 0 0"
  184. rpy="0 0 0" />
  185. <geometry>
  186. <mesh
  187. filename="package://robot_description/meshes/front_wheel_link.STL" />
  188. </geometry>
  189. </collision>
  190. </link>
  191. <joint
  192. name="front_wheel_joint"
  193. type="continuous">
  194. <origin
  195. xyz="0.075 0 -0.0023763"
  196. rpy="0 0 0" />
  197. <parent
  198. link="base_link" />
  199. <child
  200. link="front_wheel_link" />
  201. <axis
  202. xyz="0 0 -1" />
  203. </joint>
  204. <link
  205. name="back_wheel_link">
  206. <inertial>
  207. <origin
  208. xyz="-0.0152655251450065 -0.000504489640389126 -0.0275267772713533"
  209. rpy="0 0 0" />
  210. <mass
  211. value="0.0323710595794446" />
  212. <inertia
  213. ixx="5.13858672949531E-06"
  214. ixy="-7.37337358165606E-08"
  215. ixz="-2.43411911798526E-07"
  216. iyy="7.36892066003594E-06"
  217. iyz="-8.0514681280719E-09"
  218. izz="5.0594631354647E-06" />
  219. </inertial>
  220. <visual>
  221. <origin
  222. xyz="0 0 0"
  223. rpy="0 0 0" />
  224. <geometry>
  225. <mesh
  226. filename="package://robot_description/meshes/back_wheel_link.STL" />
  227. </geometry>
  228. <material
  229. name="">
  230. <color
  231. rgba="1 1 1 1" />
  232. </material>
  233. </visual>
  234. <collision>
  235. <origin
  236. xyz="0 0 0"
  237. rpy="0 0 0" />
  238. <geometry>
  239. <mesh
  240. filename="package://robot_description/meshes/back_wheel_link.STL" />
  241. </geometry>
  242. </collision>
  243. </link>
  244. <joint
  245. name="back_wheel_joint"
  246. type="continuous">
  247. <origin
  248. xyz="-0.075 0 -0.0023763"
  249. rpy="0 0 0" />
  250. <parent
  251. link="base_link" />
  252. <child
  253. link="back_wheel_link" />
  254. <axis
  255. xyz="0 0 -1" />
  256. </joint>
  257. <link
  258. name="servo_left_right_link">
  259. <inertial>
  260. <origin
  261. xyz="-0.00342029959962582 -8.31447029908761E-05 0.0164292484197976"
  262. rpy="0 0 0" />
  263. <mass
  264. value="0.0144748073722143" />
  265. <inertia
  266. ixx="1.72385755753649E-06"
  267. ixy="-4.21182747869309E-08"
  268. ixz="-2.42902265623225E-07"
  269. iyy="2.23868737048435E-06"
  270. iyz="-2.7900037637553E-08"
  271. izz="2.38358373792003E-06" />
  272. </inertial>
  273. <visual>
  274. <origin
  275. xyz="0 0 0"
  276. rpy="0 0 0" />
  277. <geometry>
  278. <mesh
  279. filename="package://robot_description/meshes/servo_left_right_link.STL" />
  280. </geometry>
  281. <material
  282. name="">
  283. <color
  284. rgba="0.647058823529412 0.647058823529412 0.647058823529412 1" />
  285. </material>
  286. </visual>
  287. <collision>
  288. <origin
  289. xyz="0 0 0"
  290. rpy="0 0 0" />
  291. <geometry>
  292. <mesh
  293. filename="package://robot_description/meshes/servo_left_right_link.STL" />
  294. </geometry>
  295. </collision>
  296. </link>
  297. <joint
  298. name="servo_left_right_joint"
  299. type="revolute">
  300. <origin
  301. xyz="0.06041 0 0.08525"
  302. rpy="0 0 0" />
  303. <parent
  304. link="base_link" />
  305. <child
  306. link="servo_left_right_link" />
  307. <axis
  308. xyz="0 0 1" />
  309. <limit
  310. lower="-1.57"
  311. upper="1.57"
  312. effort="0"
  313. velocity="0" />
  314. </joint>
  315. <link
  316. name="servo_up_down_link">
  317. <inertial>
  318. <origin
  319. xyz="0.00464326452490638 0.0203000236898356 0.00545497641365948"
  320. rpy="0 0 0" />
  321. <mass
  322. value="0.0132043090272951" />
  323. <inertia
  324. ixx="1.42353069009727E-06"
  325. ixy="1.0990050953523E-09"
  326. ixz="5.62721878758881E-09"
  327. iyy="7.90092710603907E-07"
  328. iyz="-2.31532216640704E-08"
  329. izz="9.07216677821165E-07" />
  330. </inertial>
  331. <visual>
  332. <origin
  333. xyz="0 0 0"
  334. rpy="0 0 0" />
  335. <geometry>
  336. <mesh
  337. filename="package://robot_description/meshes/servo_up_down_link.STL" />
  338. </geometry>
  339. <material
  340. name="">
  341. <color
  342. rgba="0.933333333333333 0.854901960784314 1 1" />
  343. </material>
  344. </visual>
  345. <collision>
  346. <origin
  347. xyz="0 0 0"
  348. rpy="0 0 0" />
  349. <geometry>
  350. <mesh
  351. filename="package://robot_description/meshes/servo_up_down_link.STL" />
  352. </geometry>
  353. </collision>
  354. </link>
  355. <joint
  356. name="servo_up_down_joint"
  357. type="revolute">
  358. <origin
  359. xyz="0.018197 -0.018843 0.02995"
  360. rpy="0 0 0" />
  361. <parent
  362. link="servo_left_right_link" />
  363. <child
  364. link="servo_up_down_link" />
  365. <axis
  366. xyz="-0.016183 -0.99987 0" />
  367. <limit
  368. lower="-1"
  369. upper="1"
  370. effort="0"
  371. velocity="0" />
  372. </joint>
  373. <link
  374. name="lidar">
  375. <inertial>
  376. <origin
  377. xyz="0 -2.9549326452619E-18 -6.1819252281381E-06"
  378. rpy="0 0 0" />
  379. <mass
  380. value="0.0480239560991004" />
  381. <inertia
  382. ixx="1.19703636663716E-05"
  383. ixy="8.06458768868579E-10"
  384. ixz="5.15393269333354E-24"
  385. iyy="1.19498999654021E-05"
  386. iyz="-9.10638182720746E-24"
  387. izz="2.16092905406288E-05" />
  388. </inertial>
  389. <visual>
  390. <origin
  391. xyz="0 0 0"
  392. rpy="0 0 0" />
  393. <geometry>
  394. <mesh
  395. filename="package://robot_description/meshes/lidar_link.STL" />
  396. </geometry>
  397. <material
  398. name="">
  399. <color
  400. rgba="0 0.36078431372549 0.580392156862745 1" />
  401. </material>
  402. </visual>
  403. <collision>
  404. <origin
  405. xyz="0 0 0"
  406. rpy="0 0 0" />
  407. <geometry>
  408. <mesh
  409. filename="package://robot_description/meshes/lidar_link.STL" />
  410. </geometry>
  411. </collision>
  412. </link>
  413. <joint
  414. name="lidar_joint"
  415. type="fixed">
  416. <origin
  417. xyz="-0.0021454 0 0.1992"
  418. rpy="0 0 0" />
  419. <parent
  420. link="base_link" />
  421. <child
  422. link="lidar" />
  423. <axis
  424. xyz="0 0 0" />
  425. </joint>
  426. <link
  427. name="base_imu_link">
  428. <inertial>
  429. <origin
  430. xyz="2.881138598591E-05 -0.000165484463082012 -0.00158258525002669"
  431. rpy="0 0 0" />
  432. <mass
  433. value="0.000546284032069355" />
  434. <inertia
  435. ixx="1.04502955010604E-08"
  436. ixy="5.20039658558943E-13"
  437. ixz="-3.8366937703985E-13"
  438. iyy="7.88905624806412E-09"
  439. iyz="2.70332847255175E-12"
  440. izz="1.81411505296782E-08" />
  441. </inertial>
  442. <visual>
  443. <origin
  444. xyz="0 0 0"
  445. rpy="0 0 0" />
  446. <geometry>
  447. <mesh
  448. filename="package://robot_description/meshes/imu_link.STL" />
  449. </geometry>
  450. <material
  451. name="">
  452. <color
  453. rgba="0.223529411764706 0.223529411764706 0.223529411764706 1" />
  454. </material>
  455. </visual>
  456. <collision>
  457. <origin
  458. xyz="0 0 0"
  459. rpy="0 0 0" />
  460. <geometry>
  461. <mesh
  462. filename="package://robot_description/meshes/imu_link.STL" />
  463. </geometry>
  464. </collision>
  465. </link>
  466. <joint
  467. name="imu_joint"
  468. type="fixed">
  469. <origin
  470. xyz="-0.022128 0.00056024 0.10609"
  471. rpy="0 0 0" />
  472. <parent
  473. link="base_link" />
  474. <child
  475. link="base_imu_link" />
  476. <axis
  477. xyz="0 0 0" />
  478. </joint>
  479. <link name="base_footprint">
  480. <visual>
  481. <geometry>
  482. <box size="0.005 0.005 0.005" />
  483. </geometry>
  484. </visual>
  485. </link>
  486. <joint name="base_footprint_joint" type="fixed">
  487. <origin xyz="0 0 0.05"/>
  488. <parent link="base_footprint"/>
  489. <child link="base_link"/>
  490. </joint>
  491. </robot>