pi_robot.urdf 31 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004
  1. <?xml version="1.0" ?>
  2. <!-- =================================================================================== -->
  3. <!-- | This document was autogenerated by xacro from pi_robot.xacro | -->
  4. <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
  5. <!-- =================================================================================== -->
  6. <robot name="pi_robot">
  7. <material name="white">
  8. <color rgba="0.87 0.90 0.87 1.0"/>
  9. </material>
  10. <material name="black">
  11. <color rgba="0.0 0.0 0.0 1.0"/>
  12. </material>
  13. <material name="green">
  14. <color rgba="0.22 0.32 0.14 1.0"/>
  15. </material>
  16. <material name="Green">
  17. <color rgba="0.0 0.8 0.0 1.0"/>
  18. </material>
  19. <material name="OffWhite">
  20. <color rgba="0.8 0.8 0.8 0.9"/>
  21. </material>
  22. <!-- base_footprint is a fictitious link(frame) that is on the ground right below base_link origin, navigation stack depends on this frame -->
  23. <!--
  24. <link name="base_footprint">
  25. <inertial>
  26. <mass value="0.0001" />
  27. <origin xyz="0 0 0" />
  28. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  29. iyy="0.0001" iyz="0.0"
  30. izz="0.0001" />
  31. </inertial>
  32. <visual>
  33. <origin xyz="0 0 0" rpy="0 0 0" />
  34. <geometry>
  35. <box size="0.05 0.05 0.001" />
  36. </geometry>
  37. <material name="green">
  38. <color rgba="0.2 0.8 0.2 1.0"/>
  39. </material>
  40. </visual>
  41. <collision>
  42. <origin xyz="0 0 0" rpy="0 0 0" />
  43. <geometry>
  44. <box size="0.001 0.001 0.001" />
  45. </geometry>
  46. </collision>
  47. </link>
  48. -->
  49. <link name="base_link">
  50. <inertial>
  51. <mass value="5.0"/>
  52. <origin xyz="0 0 0"/>
  53. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  54. </inertial>
  55. <visual>
  56. <origin rpy="0 0 -1.57" xyz="0 0 0.073"/>
  57. <geometry>
  58. <!--
  59. <cylinder length="0.3" radius=".15"/>
  60. -->
  61. <mesh filename="package://rbx1_description/meshes/pi_robot.dae" scale="0.0254 0.0254 0.0254"/>
  62. </geometry>
  63. <material name="grey">
  64. <color rgba="0.1 0.1 0.1 10"/>
  65. </material>
  66. </visual>
  67. <collision>
  68. <origin rpy="0 0 0" xyz="0 0 0.16"/>
  69. <geometry>
  70. <cylinder length="0.32" radius=".15"/>
  71. </geometry>
  72. </collision>
  73. </link>
  74. <!--
  75. <joint name="base_joint" type="fixed">
  76. <origin xyz="0 0 -0.073" rpy="0 0 0" />
  77. <parent link="base_link"/>
  78. <child link="base_footprint" />
  79. </joint>
  80. -->
  81. <link name="base_laser_bottom">
  82. <visual>
  83. <origin rpy="0 0 0" xyz="0 0 0"/>
  84. <geometry>
  85. <box size="0.05 0.05 0.041"/>
  86. </geometry>
  87. <material name="black">
  88. <color rgba="0.1 0.1 0.1 1.0"/>
  89. </material>
  90. </visual>
  91. <collision>
  92. <origin rpy="0 0 0" xyz="0 0 0"/>
  93. <geometry>
  94. <box size="0.05 0.05 0.041"/>
  95. </geometry>
  96. </collision>
  97. <inertial>
  98. <mass value="0.1"/>
  99. <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
  100. </inertial>
  101. </link>
  102. <joint name="base_laser_bottom_joint" type="fixed">
  103. <parent link="base_link"/>
  104. <child link="base_laser_bottom"/>
  105. <origin rpy="0 0 0" xyz="0.123 0 0.0995"/>
  106. </joint>
  107. <link name="base_laser_middle">
  108. <visual>
  109. <origin rpy="0 0 0" xyz="0 0 0"/>
  110. <geometry>
  111. <cylinder length="0.0115" radius=".02"/>
  112. </geometry>
  113. <material name="dark_grey">
  114. <color rgba="0.2 0.2 0.2 1.0"/>
  115. </material>
  116. </visual>
  117. <collision>
  118. <origin rpy="0 0 0" xyz="0 0 0"/>
  119. <geometry>
  120. <cylinder length="0.0115" radius=".02"/>
  121. </geometry>
  122. </collision>
  123. <inertial>
  124. <mass value="0.1"/>
  125. <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
  126. </inertial>
  127. </link>
  128. <joint name="base_laser_middle_joint" type="fixed">
  129. <parent link="base_laser_bottom"/>
  130. <child link="base_laser_middle"/>
  131. <origin rpy="0 0 0" xyz="0 0 0.02625"/>
  132. </joint>
  133. <link name="base_laser">
  134. <visual>
  135. <origin rpy="0 0 0" xyz="0 0 0"/>
  136. <geometry>
  137. <cylinder length="0.0175" radius=".0185"/>
  138. </geometry>
  139. <material name="red">
  140. <color rgba="0.8 0.1 0.1 1.0"/>
  141. </material>
  142. </visual>
  143. <collision>
  144. <origin rpy="0 0 0" xyz="0 0 0"/>
  145. <geometry>
  146. <cylinder length="0.0175" radius=".0185"/>
  147. </geometry>
  148. </collision>
  149. <inertial>
  150. <mass value="0.1"/>
  151. <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
  152. </inertial>
  153. </link>
  154. <joint name="base_laser_joint" type="fixed">
  155. <parent link="base_laser_middle"/>
  156. <child link="base_laser"/>
  157. <origin rpy="0 0 0" xyz="0 0 0.0145"/>
  158. </joint>
  159. <!-- Attach the head -->
  160. <link name="head_base_link"/>
  161. <joint name="head_base_joint" type="fixed">
  162. <origin xyz="0.064 0 0.871"/>
  163. <parent link="base_link"/>
  164. <child link="head_base_link"/>
  165. </joint>
  166. <link name="head_pan_link"/>
  167. <joint name="fake_head_pan_joint" type="fixed">
  168. <origin rpy="0 1.570795 1.570795" xyz="0 0 0"/>
  169. <parent link="head_pan_servo_link"/>
  170. <child link="head_pan_link"/>
  171. </joint>
  172. <link name="head_tilt_link"/>
  173. <joint name="fake_head_tilt_joint" type="fixed">
  174. <origin rpy="0 0 3.14159" xyz="0 0 0"/>
  175. <parent link="head_tilt_servo_link"/>
  176. <child link="head_tilt_link"/>
  177. </joint>
  178. <joint name="head_pan_servo_joint" type="fixed">
  179. <origin rpy="1.570795 0 -1.570795" xyz="0 0 -0.019"/>
  180. <parent link="head_base_link"/>
  181. <child link="head_pan_servo_link"/>
  182. </joint>
  183. <link name="head_pan_servo_link">
  184. <inertial>
  185. <mass value="0.00001"/>
  186. <origin xyz="0 0 0"/>
  187. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  188. </inertial>
  189. <visual>
  190. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  191. <geometry>
  192. <mesh filename="package://rbx1_description/meshes/ax12_box.dae" scale="100 100 100"/>
  193. </geometry>
  194. <material name="black"/>
  195. </visual>
  196. <collision>
  197. <origin rpy="0 0 0" xyz="0.0 0.0 -0.01241"/>
  198. <geometry>
  199. <box size="0.025 0.038 0.04762"/>
  200. </geometry>
  201. </collision>
  202. </link>
  203. <joint name="head_pan_joint" type="revolute">
  204. <origin rpy="-1.570795 1.570795 3.14159" xyz="0 0.024 0.0"/>
  205. <parent link="head_pan_servo_link"/>
  206. <axis xyz="0 0 -1"/>
  207. <limit effort="30" lower="-2.9" upper="2.9" velocity="1.0"/>
  208. <child link="bioloid_F3_head_10_link"/>
  209. </joint>
  210. <link name="bioloid_F3_head_10_link">
  211. <inertial>
  212. <mass value="0.00001"/>
  213. <origin xyz="0 0 0"/>
  214. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  215. </inertial>
  216. <visual>
  217. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  218. <geometry>
  219. <mesh filename="package://rbx1_description/meshes/F3.dae" scale="0.001 0.001 0.001"/>
  220. </geometry>
  221. <material name="white"/>
  222. </visual>
  223. <collision>
  224. <origin rpy="0 0 0" xyz="0.0 0.0 -0.0045"/>
  225. <geometry>
  226. <box size="0.025 0.038 0.009"/>
  227. </geometry>
  228. </collision>
  229. </link>
  230. <joint name="head_tilt_servo_joint" type="fixed">
  231. <origin rpy="0 3.14159 0" xyz="0 0 -0.0415"/>
  232. <parent link="bioloid_F3_head_10_link"/>
  233. <child link="head_tilt_servo_link"/>
  234. </joint>
  235. <link name="head_tilt_servo_link">
  236. <inertial>
  237. <mass value="0.00001"/>
  238. <origin xyz="0 0 0"/>
  239. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  240. </inertial>
  241. <visual>
  242. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  243. <geometry>
  244. <mesh filename="package://rbx1_description/meshes/ax12_box.dae" scale="100 100 100"/>
  245. </geometry>
  246. <material name="black"/>
  247. </visual>
  248. <collision>
  249. <origin rpy="0 0 0" xyz="0.0 0.0 -0.01241"/>
  250. <geometry>
  251. <box size="0.025 0.038 0.04762"/>
  252. </geometry>
  253. </collision>
  254. </link>
  255. <joint name="head_tilt_joint" type="revolute">
  256. <origin rpy="0 0 0" xyz="0 0 0"/>
  257. <parent link="head_tilt_servo_link"/>
  258. <axis xyz="0 -1 0"/>
  259. <limit effort="30" lower="-2.9" upper="2.9" velocity="1.0"/>
  260. <child link="bioloid_F4_head_10_link"/>
  261. </joint>
  262. <link name="bioloid_F4_head_10_link">
  263. <inertial>
  264. <mass value="0.00001"/>
  265. <origin xyz="0 0 0"/>
  266. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  267. </inertial>
  268. <visual>
  269. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  270. <geometry>
  271. <mesh filename="package://rbx1_description/meshes/F4.dae" scale="0.001 0.001 0.001"/>
  272. </geometry>
  273. <material name="white"/>
  274. </visual>
  275. <collision>
  276. <origin rpy="0 0 0" xyz="0.0 0.0 0.0215"/>
  277. <geometry>
  278. <box size="0.028 0.0485 0.065"/>
  279. </geometry>
  280. </collision>
  281. </link>
  282. <joint name="head_tilt_bracket_joint" type="fixed">
  283. <origin rpy="0 0 0" xyz="0 0 0.0545"/>
  284. <parent link="bioloid_F4_head_10_link"/>
  285. <child link="head_tilt_bracket_link"/>
  286. </joint>
  287. <link name="head_tilt_bracket_link">
  288. <inertial>
  289. <mass value="0.00001"/>
  290. <origin xyz="0 0 0"/>
  291. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  292. </inertial>
  293. <visual>
  294. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  295. <geometry>
  296. <mesh filename="package://rbx1_description/meshes/F10.dae" scale="0.001 0.001 0.001"/>
  297. </geometry>
  298. <material name="white"/>
  299. </visual>
  300. <collision>
  301. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  302. <geometry>
  303. <box size="0.025 0.038 0.004"/>
  304. </geometry>
  305. </collision>
  306. </link>
  307. <joint name="base_kinect_joint" type="fixed">
  308. <origin rpy="0 0 3.14159" xyz="-0.03 0 0.058"/>
  309. <parent link="head_tilt_bracket_link"/>
  310. <child link="kinect_link"/>
  311. </joint>
  312. <link name="kinect_link">
  313. <inertial>
  314. <mass value="0.00001"/>
  315. <origin xyz="0 0 0"/>
  316. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  317. </inertial>
  318. <visual>
  319. <origin rpy="0 0 0" xyz="0 0 0 "/>
  320. <geometry>
  321. <mesh filename="package://rbx1_description/meshes/kinect.dae" scale="100 100 100"/>
  322. </geometry>
  323. </visual>
  324. <collision>
  325. <origin rpy="0 0 0" xyz="-0.0275 0.0 0.0"/>
  326. <geometry>
  327. <box size="0.0730 .2760 0.0720"/>
  328. </geometry>
  329. </collision>
  330. </link>
  331. <joint name="kinect_depth_joint" type="fixed">
  332. <origin rpy="0 0 0" xyz="0 0.018 0"/>
  333. <parent link="kinect_link"/>
  334. <child link="kinect_depth_frame"/>
  335. </joint>
  336. <link name="kinect_depth_frame">
  337. <inertial>
  338. <mass value="0.000001"/>
  339. <origin xyz="0 0 0"/>
  340. <inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
  341. </inertial>
  342. </link>
  343. <joint name="kinect_depth_optical_joint" type="fixed">
  344. <origin rpy="-1.570795 0 -1.570795" xyz="0 0 0"/>
  345. <parent link="kinect_depth_frame"/>
  346. <child link="kinect_depth_optical_frame"/>
  347. </joint>
  348. <link name="kinect_depth_optical_frame">
  349. <inertial>
  350. <mass value="0.000001"/>
  351. <origin xyz="0 0 0"/>
  352. <inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
  353. </inertial>
  354. </link>
  355. <joint name="kinect_rgb_joint" type="fixed">
  356. <origin rpy="0 0 0" xyz="0 -0.005 0"/>
  357. <parent link="kinect_link"/>
  358. <child link="kinect_rgb_frame"/>
  359. </joint>
  360. <link name="kinect_rgb_frame">
  361. <inertial>
  362. <mass value="0.000001"/>
  363. <origin xyz="0 0 0"/>
  364. <inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
  365. </inertial>
  366. </link>
  367. <joint name="kinect_rgb_optical_joint" type="fixed">
  368. <origin rpy="-1.570795 0 -1.570795" xyz="0 0 0"/>
  369. <parent link="kinect_rgb_frame"/>
  370. <child link="kinect_rgb_optical_frame"/>
  371. </joint>
  372. <link name="kinect_rgb_optical_frame">
  373. <inertial>
  374. <mass value="0.000001"/>
  375. <origin xyz="0 0 0"/>
  376. <inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
  377. </inertial>
  378. </link>
  379. <link name="left_eye_link">
  380. <visual>
  381. <origin rpy="0 1.57 0" xyz="0 0 0"/>
  382. <geometry>
  383. <cylinder length="0.01" radius="0.01"/>
  384. </geometry>
  385. <material name="OffWhite"/>
  386. </visual>
  387. <collision>
  388. <origin rpy="0 1.57 0" xyz="0 0 0"/>
  389. <geometry>
  390. <cylinder length="0.01" radius="0.01"/>
  391. </geometry>
  392. </collision>
  393. <inertial>
  394. <mass value="0.00001"/>
  395. <origin xyz="0 0 0"/>
  396. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  397. </inertial>
  398. </link>
  399. <link name="right_eye_link">
  400. <visual>
  401. <origin rpy="0 1.57 0" xyz="0 0 0"/>
  402. <geometry>
  403. <cylinder length="0.01" radius="0.01"/>
  404. </geometry>
  405. <material name="OffWhite"/>
  406. </visual>
  407. <collision>
  408. <origin rpy="0 1.57 0" xyz="0 0 0"/>
  409. <geometry>
  410. <cylinder length="0.01" radius="0.01"/>
  411. </geometry>
  412. </collision>
  413. <inertial>
  414. <mass value="0.00001"/>
  415. <origin xyz="0 0 0"/>
  416. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  417. </inertial>
  418. </link>
  419. <joint name="left_eye_joint" type="fixed">
  420. <parent link="kinect_link"/>
  421. <child link="left_eye_link"/>
  422. <origin rpy="0 0 0" xyz="-0.005 0.035 0"/>
  423. </joint>
  424. <joint name="right_eye_joint" type="fixed">
  425. <parent link="kinect_link"/>
  426. <child link="right_eye_link"/>
  427. <origin rpy="0 0 0" xyz="-0.005 -0.035 0"/>
  428. </joint>
  429. <!-- Attach the arm -->
  430. <link name="arm_base_link"/>
  431. <joint name="arm_base_joint" type="fixed">
  432. <origin rpy="0 0 1.57" xyz="0.125 0.06 0.6615"/>
  433. <parent link="base_link"/>
  434. <child link="arm_base_link"/>
  435. </joint>
  436. <link name="gripper_link"/>
  437. <joint name="gripper_link_joint" type="fixed">
  438. <origin rpy="0 -1.570795 0" xyz="0 0 .112"/>
  439. <parent link="arm_wrist_flex_link"/>
  440. <child link="gripper_link"/>
  441. </joint>
  442. <joint name="arm_shoulder_pan_servo_joint" type="fixed">
  443. <origin rpy="1.570795 0 1.570795" xyz="0 0 0"/>
  444. <parent link="arm_base_link"/>
  445. <child link="arm_shoulder_pan_servo_link"/>
  446. </joint>
  447. <link name="arm_shoulder_pan_servo_link">
  448. <inertial>
  449. <mass value="0.00001"/>
  450. <origin xyz="0 0 0"/>
  451. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  452. </inertial>
  453. <visual>
  454. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  455. <geometry>
  456. <mesh filename="package://rbx1_description/meshes/ax12_box.dae" scale="100 100 100"/>
  457. </geometry>
  458. <material name="black"/>
  459. </visual>
  460. <collision>
  461. <origin rpy="0 0 0" xyz="0.0 0.0 -0.01241"/>
  462. <geometry>
  463. <box size="0.025 0.038 0.04762"/>
  464. </geometry>
  465. </collision>
  466. </link>
  467. <joint name="arm_shoulder_pan_joint" type="revolute">
  468. <origin rpy="-1.570795 1.570795 3.14159" xyz="0 0.019 0"/>
  469. <axis xyz="0 0 -1"/>
  470. <limit effort="30" lower="-2.617" upper="2.617" velocity="0.785"/>
  471. <parent link="arm_shoulder_pan_servo_link"/>
  472. <child link="arm_shoulder_pan_link"/>
  473. </joint>
  474. <link name="arm_shoulder_pan_link">
  475. <inertial>
  476. <mass value="0.00001"/>
  477. <origin xyz="0 0 0"/>
  478. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  479. </inertial>
  480. <visual>
  481. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  482. <geometry>
  483. <mesh filename="package://rbx1_description/meshes/F3.dae" scale="0.001 0.001 0.001"/>
  484. </geometry>
  485. <material name="white"/>
  486. </visual>
  487. <collision>
  488. <origin rpy="0 0 0" xyz="0.0 0.0 -0.0045"/>
  489. <geometry>
  490. <box size="0.025 0.038 0.009"/>
  491. </geometry>
  492. </collision>
  493. </link>
  494. <joint name="arm_shoulder_lift_servo_joint" type="fixed">
  495. <origin rpy="0 3.14159 0" xyz="0 0 -0.0415"/>
  496. <parent link="arm_shoulder_pan_link"/>
  497. <child link="arm_shoulder_lift_servo_link"/>
  498. </joint>
  499. <link name="arm_shoulder_lift_servo_link">
  500. <inertial>
  501. <mass value="0.00001"/>
  502. <origin xyz="0 0 0"/>
  503. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  504. </inertial>
  505. <visual>
  506. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  507. <geometry>
  508. <mesh filename="package://rbx1_description/meshes/ax12_box.dae" scale="100 100 100"/>
  509. </geometry>
  510. <material name="black"/>
  511. </visual>
  512. <collision>
  513. <origin rpy="0 0 0" xyz="0.0 0.0 -0.01241"/>
  514. <geometry>
  515. <box size="0.025 0.038 0.04762"/>
  516. </geometry>
  517. </collision>
  518. </link>
  519. <joint name="arm_shoulder_lift_joint" type="revolute">
  520. <origin rpy="0 0 0" xyz="0 0 0"/>
  521. <axis xyz="0 1 0"/>
  522. <limit effort="30" lower="-2.617" upper="2.617" velocity="1.571"/>
  523. <parent link="arm_shoulder_lift_servo_link"/>
  524. <child link="arm_shoulder_lift_link"/>
  525. </joint>
  526. <link name="arm_shoulder_lift_link">
  527. <inertial>
  528. <mass value="0.00001"/>
  529. <origin xyz="0 0 0"/>
  530. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  531. </inertial>
  532. <visual>
  533. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  534. <geometry>
  535. <mesh filename="package://rbx1_description/meshes/F4.dae" scale="0.001 0.001 0.001"/>
  536. </geometry>
  537. <material name="white"/>
  538. </visual>
  539. <collision>
  540. <origin rpy="0 0 0" xyz="0.0 0.0 0.0215"/>
  541. <geometry>
  542. <box size="0.028 0.0485 0.065"/>
  543. </geometry>
  544. </collision>
  545. </link>
  546. <joint name="arm_shoulder_F10_0_joint" type="fixed">
  547. <origin rpy="0 0 0" xyz="0 0 0.0545"/>
  548. <parent link="arm_shoulder_lift_link"/>
  549. <child link="arm_shoulder_F10_0_link"/>
  550. </joint>
  551. <link name="arm_shoulder_F10_0_link">
  552. <inertial>
  553. <mass value="0.00001"/>
  554. <origin xyz="0 0 0"/>
  555. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  556. </inertial>
  557. <visual>
  558. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  559. <geometry>
  560. <mesh filename="package://rbx1_description/meshes/F10.dae" scale="0.001 0.001 0.001"/>
  561. </geometry>
  562. <material name="white"/>
  563. </visual>
  564. <collision>
  565. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  566. <geometry>
  567. <box size="0.025 0.038 0.004"/>
  568. </geometry>
  569. </collision>
  570. </link>
  571. <joint name="arm_shoulder_F10_1_joint" type="fixed">
  572. <origin rpy="0 0 0" xyz="0 0 0.004"/>
  573. <parent link="arm_shoulder_F10_0_link"/>
  574. <child link="arm_shoulder_F10_1_link"/>
  575. </joint>
  576. <link name="arm_shoulder_F10_1_link">
  577. <inertial>
  578. <mass value="0.00001"/>
  579. <origin xyz="0 0 0"/>
  580. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  581. </inertial>
  582. <visual>
  583. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  584. <geometry>
  585. <mesh filename="package://rbx1_description/meshes/F10.dae" scale="0.001 0.001 0.001"/>
  586. </geometry>
  587. <material name="white"/>
  588. </visual>
  589. <collision>
  590. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  591. <geometry>
  592. <box size="0.025 0.038 0.004"/>
  593. </geometry>
  594. </collision>
  595. </link>
  596. <joint name="arm_shoulder_F10_2_joint" type="fixed">
  597. <origin rpy="0 0 0" xyz="0 0 0.004"/>
  598. <parent link="arm_shoulder_F10_1_link"/>
  599. <child link="arm_shoulder_F10_2_link"/>
  600. </joint>
  601. <link name="arm_shoulder_F10_2_link">
  602. <inertial>
  603. <mass value="0.00001"/>
  604. <origin xyz="0 0 0"/>
  605. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  606. </inertial>
  607. <visual>
  608. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  609. <geometry>
  610. <mesh filename="package://rbx1_description/meshes/F10.dae" scale="0.001 0.001 0.001"/>
  611. </geometry>
  612. <material name="white"/>
  613. </visual>
  614. <collision>
  615. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  616. <geometry>
  617. <box size="0.025 0.038 0.004"/>
  618. </geometry>
  619. </collision>
  620. </link>
  621. <joint name="arm_shoulder_F3_0_joint" type="fixed">
  622. <origin rpy="0 3.14159 0" xyz="0 0 0.002"/>
  623. <parent link="arm_shoulder_F10_2_link"/>
  624. <child link="arm_shoulder_F3_0_link"/>
  625. </joint>
  626. <link name="arm_shoulder_F3_0_link">
  627. <inertial>
  628. <mass value="0.00001"/>
  629. <origin xyz="0 0 0"/>
  630. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  631. </inertial>
  632. <visual>
  633. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  634. <geometry>
  635. <mesh filename="package://rbx1_description/meshes/F3.dae" scale="0.001 0.001 0.001"/>
  636. </geometry>
  637. <material name="white"/>
  638. </visual>
  639. <collision>
  640. <origin rpy="0 0 0" xyz="0.0 0.0 -0.0045"/>
  641. <geometry>
  642. <box size="0.025 0.038 0.009"/>
  643. </geometry>
  644. </collision>
  645. </link>
  646. <joint name="arm_elbow_flex_servo_joint" type="fixed">
  647. <origin rpy="0 3.14159 0" xyz="0 0 -0.0415"/>
  648. <parent link="arm_shoulder_F3_0_link"/>
  649. <child link="arm_elbow_flex_servo_link"/>
  650. </joint>
  651. <link name="arm_elbow_flex_servo_link">
  652. <inertial>
  653. <mass value="0.00001"/>
  654. <origin xyz="0 0 0"/>
  655. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  656. </inertial>
  657. <visual>
  658. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  659. <geometry>
  660. <mesh filename="package://rbx1_description/meshes/ax12_box.dae" scale="100 100 100"/>
  661. </geometry>
  662. <material name="black"/>
  663. </visual>
  664. <collision>
  665. <origin rpy="0 0 0" xyz="0.0 0.0 -0.01241"/>
  666. <geometry>
  667. <box size="0.025 0.038 0.04762"/>
  668. </geometry>
  669. </collision>
  670. </link>
  671. <joint name="arm_elbow_flex_joint" type="revolute">
  672. <origin rpy="0 0 0" xyz="0 0 0"/>
  673. <axis xyz="0 1 0"/>
  674. <limit effort="30" lower="-2.617" upper="2.617" velocity="1.571"/>
  675. <parent link="arm_elbow_flex_servo_link"/>
  676. <child link="arm_elbow_flex_link"/>
  677. </joint>
  678. <link name="arm_elbow_flex_link">
  679. <inertial>
  680. <mass value="0.00001"/>
  681. <origin xyz="0 0 0"/>
  682. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  683. </inertial>
  684. <visual>
  685. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  686. <geometry>
  687. <mesh filename="package://rbx1_description/meshes/F4.dae" scale="0.001 0.001 0.001"/>
  688. </geometry>
  689. <material name="white"/>
  690. </visual>
  691. <collision>
  692. <origin rpy="0 0 0" xyz="0.0 0.0 0.0215"/>
  693. <geometry>
  694. <box size="0.028 0.0485 0.065"/>
  695. </geometry>
  696. </collision>
  697. </link>
  698. <joint name="arm_elbow_F10_0_joint" type="fixed">
  699. <origin rpy="0 0 0" xyz="0 0 0.0545"/>
  700. <parent link="arm_elbow_flex_link"/>
  701. <child link="arm_elbow_F10_0_link"/>
  702. </joint>
  703. <link name="arm_elbow_F10_0_link">
  704. <inertial>
  705. <mass value="0.00001"/>
  706. <origin xyz="0 0 0"/>
  707. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  708. </inertial>
  709. <visual>
  710. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  711. <geometry>
  712. <mesh filename="package://rbx1_description/meshes/F10.dae" scale="0.001 0.001 0.001"/>
  713. </geometry>
  714. <material name="white"/>
  715. </visual>
  716. <collision>
  717. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  718. <geometry>
  719. <box size="0.025 0.038 0.004"/>
  720. </geometry>
  721. </collision>
  722. </link>
  723. <joint name="arm_elbow_F10_1_joint" type="fixed">
  724. <origin rpy="0 0 0" xyz="0 0 0.004"/>
  725. <parent link="arm_elbow_F10_0_link"/>
  726. <child link="arm_elbow_F10_1_link"/>
  727. </joint>
  728. <link name="arm_elbow_F10_1_link">
  729. <inertial>
  730. <mass value="0.00001"/>
  731. <origin xyz="0 0 0"/>
  732. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  733. </inertial>
  734. <visual>
  735. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  736. <geometry>
  737. <mesh filename="package://rbx1_description/meshes/F10.dae" scale="0.001 0.001 0.001"/>
  738. </geometry>
  739. <material name="white"/>
  740. </visual>
  741. <collision>
  742. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  743. <geometry>
  744. <box size="0.025 0.038 0.004"/>
  745. </geometry>
  746. </collision>
  747. </link>
  748. <joint name="arm_elbow_F10_2_joint" type="fixed">
  749. <origin rpy="0 0 0" xyz="0 0 0.004"/>
  750. <parent link="arm_elbow_F10_1_link"/>
  751. <child link="arm_elbow_F10_2_link"/>
  752. </joint>
  753. <link name="arm_elbow_F10_2_link">
  754. <inertial>
  755. <mass value="0.00001"/>
  756. <origin xyz="0 0 0"/>
  757. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  758. </inertial>
  759. <visual>
  760. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  761. <geometry>
  762. <mesh filename="package://rbx1_description/meshes/F10.dae" scale="0.001 0.001 0.001"/>
  763. </geometry>
  764. <material name="white"/>
  765. </visual>
  766. <collision>
  767. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  768. <geometry>
  769. <box size="0.025 0.038 0.004"/>
  770. </geometry>
  771. </collision>
  772. </link>
  773. <joint name="arm_elbow_F3_0_joint" type="fixed">
  774. <origin rpy="0 3.14159 0" xyz="0 0 0.002"/>
  775. <parent link="arm_elbow_F10_2_link"/>
  776. <child link="arm_elbow_F3_0_link"/>
  777. </joint>
  778. <link name="arm_elbow_F3_0_link">
  779. <inertial>
  780. <mass value="0.00001"/>
  781. <origin xyz="0 0 0"/>
  782. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  783. </inertial>
  784. <visual>
  785. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  786. <geometry>
  787. <mesh filename="package://rbx1_description/meshes/F3.dae" scale="0.001 0.001 0.001"/>
  788. </geometry>
  789. <material name="white"/>
  790. </visual>
  791. <collision>
  792. <origin rpy="0 0 0" xyz="0.0 0.0 -0.0045"/>
  793. <geometry>
  794. <box size="0.025 0.038 0.009"/>
  795. </geometry>
  796. </collision>
  797. </link>
  798. <joint name="arm_wrist_flex_servo_joint" type="fixed">
  799. <origin rpy="0 3.14159 0" xyz="0 0 -0.0415"/>
  800. <parent link="arm_elbow_F3_0_link"/>
  801. <child link="arm_wrist_flex_servo_link"/>
  802. </joint>
  803. <link name="arm_wrist_flex_servo_link">
  804. <inertial>
  805. <mass value="0.00001"/>
  806. <origin xyz="0 0 0"/>
  807. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  808. </inertial>
  809. <visual>
  810. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  811. <geometry>
  812. <mesh filename="package://rbx1_description/meshes/ax12_box.dae" scale="100 100 100"/>
  813. </geometry>
  814. <material name="black"/>
  815. </visual>
  816. <collision>
  817. <origin rpy="0 0 0" xyz="0.0 0.0 -0.01241"/>
  818. <geometry>
  819. <box size="0.025 0.038 0.04762"/>
  820. </geometry>
  821. </collision>
  822. </link>
  823. <joint name="arm_wrist_flex_joint" type="revolute">
  824. <origin rpy="0 0 0" xyz="0 0 0"/>
  825. <axis xyz="0 1 0"/>
  826. <limit effort="30" lower="-1.745" upper="1.745" velocity="1.571"/>
  827. <parent link="arm_wrist_flex_servo_link"/>
  828. <child link="arm_wrist_flex_link"/>
  829. </joint>
  830. <link name="arm_wrist_flex_link">
  831. <inertial>
  832. <mass value="0.00001"/>
  833. <origin xyz="0 0 0"/>
  834. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  835. </inertial>
  836. <visual>
  837. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  838. <geometry>
  839. <mesh filename="package://rbx1_description/meshes/F2.dae" scale="0.001 0.001 0.001"/>
  840. </geometry>
  841. <material name="white"/>
  842. </visual>
  843. <collision>
  844. <origin rpy="0 0 0" xyz="0.0 0.0 0.00775"/>
  845. <geometry>
  846. <box size="0.025 0.0485 0.0375"/>
  847. </geometry>
  848. </collision>
  849. </link>
  850. <joint name="arm_wrist_F3_0_joint" type="fixed">
  851. <origin rpy="0 3.14159 -1.570795" xyz="0 0.016 0.0265"/>
  852. <parent link="arm_wrist_flex_link"/>
  853. <child link="arm_wrist_F3_0_link"/>
  854. </joint>
  855. <link name="arm_wrist_F3_0_link">
  856. <inertial>
  857. <mass value="0.00001"/>
  858. <origin xyz="0 0 0"/>
  859. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  860. </inertial>
  861. <visual>
  862. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  863. <geometry>
  864. <mesh filename="package://rbx1_description/meshes/F3.dae" scale="0.001 0.001 0.001"/>
  865. </geometry>
  866. <material name="white"/>
  867. </visual>
  868. <collision>
  869. <origin rpy="0 0 0" xyz="0.0 0.0 -0.0045"/>
  870. <geometry>
  871. <box size="0.025 0.038 0.009"/>
  872. </geometry>
  873. </collision>
  874. </link>
  875. <joint name="gripper_servo_joint" type="fixed">
  876. <origin rpy="3.14159 1.570795 0" xyz="-0.02275 0 -0.019"/>
  877. <parent link="arm_wrist_F3_0_link"/>
  878. <child link="gripper_servo_link"/>
  879. </joint>
  880. <link name="gripper_servo_link">
  881. <inertial>
  882. <mass value="0.00001"/>
  883. <origin xyz="0 0 0"/>
  884. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  885. </inertial>
  886. <visual>
  887. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  888. <geometry>
  889. <mesh filename="package://rbx1_description/meshes/ax12_box.dae" scale="100 100 100"/>
  890. </geometry>
  891. <material name="black"/>
  892. </visual>
  893. <collision>
  894. <origin rpy="0 0 0" xyz="0.0 0.0 -0.01241"/>
  895. <geometry>
  896. <box size="0.025 0.038 0.04762"/>
  897. </geometry>
  898. </collision>
  899. </link>
  900. <joint name="gripper_joint" type="revolute">
  901. <origin rpy="0 0 0" xyz="0 0 0"/>
  902. <axis xyz="0 1 0"/>
  903. <limit effort="30" lower="-0.060" upper="0.50" velocity="0.785"/>
  904. <parent link="gripper_servo_link"/>
  905. <child link="gripper_active_link"/>
  906. </joint>
  907. <link name="gripper_active_link">
  908. <inertial>
  909. <mass value="0.00001"/>
  910. <origin xyz="0 0 0"/>
  911. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  912. </inertial>
  913. <visual>
  914. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  915. <geometry>
  916. <mesh filename="package://rbx1_description/meshes/F2.dae" scale="0.001 0.001 0.001"/>
  917. </geometry>
  918. <material name="white"/>
  919. </visual>
  920. <collision>
  921. <origin rpy="0 0 0" xyz="0.0 0.0 0.00775"/>
  922. <geometry>
  923. <box size="0.025 0.0485 0.0375"/>
  924. </geometry>
  925. </collision>
  926. </link>
  927. <joint name="gripper_active_finger_joint" type="fixed">
  928. <origin rpy="0 0 0" xyz="0 0 0.0265"/>
  929. <parent link="gripper_active_link"/>
  930. <child link="gripper_active_finger_link"/>
  931. </joint>
  932. <link name="gripper_active_finger_link">
  933. <inertial>
  934. <mass value="0.00001"/>
  935. <origin xyz="0 0 0"/>
  936. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  937. </inertial>
  938. <visual>
  939. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  940. <geometry>
  941. <mesh filename="package://rbx1_description/meshes/finger.dae" scale="0.001 0.001 0.001"/>
  942. </geometry>
  943. <material name="green"/>
  944. </visual>
  945. <collision>
  946. <origin rpy="0 0 0" xyz="0.02645 0.0 -0.00655"/>
  947. <geometry>
  948. <box size="0.0783 0.03801 0.0193"/>
  949. </geometry>
  950. </collision>
  951. </link>
  952. <joint name="gripper_static_joint" type="fixed">
  953. <origin rpy="0 3.14159 0" xyz="0 0 -0.0415"/>
  954. <parent link="gripper_servo_link"/>
  955. <child link="gripper_static_link"/>
  956. </joint>
  957. <link name="gripper_static_link">
  958. <inertial>
  959. <mass value="0.00001"/>
  960. <origin xyz="0 0 0"/>
  961. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  962. </inertial>
  963. <visual>
  964. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  965. <geometry>
  966. <mesh filename="package://rbx1_description/meshes/F3.dae" scale="0.001 0.001 0.001"/>
  967. </geometry>
  968. <material name="white"/>
  969. </visual>
  970. <collision>
  971. <origin rpy="0 0 0" xyz="0.0 0.0 -0.0045"/>
  972. <geometry>
  973. <box size="0.025 0.038 0.009"/>
  974. </geometry>
  975. </collision>
  976. </link>
  977. <joint name="gripper_static_finger_joint" type="fixed">
  978. <origin rpy="0 0 3.14159" xyz="0 0 0"/>
  979. <parent link="gripper_static_link"/>
  980. <child link="gripper_static_finger_link"/>
  981. </joint>
  982. <link name="gripper_static_finger_link">
  983. <inertial>
  984. <mass value="0.00001"/>
  985. <origin xyz="0 0 0"/>
  986. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  987. </inertial>
  988. <visual>
  989. <origin rpy="0 0 0" xyz=" 0 0 0 "/>
  990. <geometry>
  991. <mesh filename="package://rbx1_description/meshes/finger.dae" scale="0.001 0.001 0.001"/>
  992. </geometry>
  993. <material name="green"/>
  994. </visual>
  995. <collision>
  996. <origin rpy="0 0 0" xyz="0.02645 0.0 -0.00655"/>
  997. <geometry>
  998. <box size="0.0783 0.03801 0.0193"/>
  999. </geometry>
  1000. </collision>
  1001. </link>
  1002. </robot>