robot_description.urdf 62 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784
  1. <?xml version="1.0" encoding="utf-8"?>
  2. <!-- =================================================================================== -->
  3. <!-- | This document was autogenerated by xacro from /opt/hector/share/drz_telemax_description/urdf/drz_telemax_complete.urdf.xacro | -->
  4. <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
  5. <!-- =================================================================================== -->
  6. <robot name="drz_telemax">
  7. <!--TODO wenn Kamera auf Handgelenk gesteckt wird, aendern sich die Werte-->
  8. <material name="Black">
  9. <color rgba="0.0 0.0 0.0 1.0"/>
  10. </material>
  11. <material name="LightBlack">
  12. <color rgba="0.25 0.25 0.25 1.0"/>
  13. </material>
  14. <material name="Blue">
  15. <color rgba="0.0 0.0 0.8 1.0"/>
  16. </material>
  17. <material name="Green">
  18. <color rgba="0.0 0.8 0.0 1.0"/>
  19. </material>
  20. <material name="Gray">
  21. <color rgba="0.7 0.7 0.7 1.0"/>
  22. </material>
  23. <material name="LightGray">
  24. <color rgba="0.9 0.9 0.9 1.0"/>
  25. </material>
  26. <material name="LightGray2">
  27. <color rgba="0.6 0.6 0.6 1.0"/>
  28. </material>
  29. <material name="DarkGray">
  30. <color rgba="0.5 0.5 0.5 1.0"/>
  31. </material>
  32. <material name="DarkGray2">
  33. <color rgba="0.3 0.3 0.3 1.0"/>
  34. </material>
  35. <material name="Red">
  36. <color rgba="0.8 0.0 0.0 1.0"/>
  37. </material>
  38. <material name="White">
  39. <color rgba="1.0 1.0 1.0 1.0"/>
  40. </material>
  41. <material name="Orange">
  42. <color rgba="1.0 0.5 0.0 1.0"/>
  43. </material>
  44. <material name="Front">
  45. <color rgba="1.0 0.25 0.0 1.0"/>
  46. </material>
  47. <material name="Rear">
  48. <color rgba="0.0 0.5 1.0 1.0"/>
  49. </material>
  50. <!-- Measured from CAD file -->
  51. <!-- Measured from CAD file -->
  52. <link name="base_link"/>
  53. <joint name="chassis_joint" type="fixed">
  54. <origin rpy="0 0 0" xyz="0 0 0"/>
  55. <parent link="base_link"/>
  56. <child link="chassis_link"/>
  57. </joint>
  58. <!-- robot chassis link -->
  59. <link name="chassis_link">
  60. <inertial>
  61. <origin rpy="0 0 0" xyz="0 0 0.05"/>
  62. <mass value="40"/>
  63. <inertia ixx="0.376333333333" ixy="0.0" ixz="0.0" iyy="1.54166666667" iyz="0.0" izz="1.65133333333"/>
  64. </inertial>
  65. <visual>
  66. <origin rpy="0 0 0" xyz="0 0 0"/>
  67. <geometry>
  68. <mesh filename="package://drz_telemax_description/meshes/maxpro_chassis.dae" scale="0.001 0.001 0.001"/>
  69. </geometry>
  70. </visual>
  71. <visual>
  72. <origin rpy="0 0 0" xyz="-0.125 0.0 0.225"/>
  73. <geometry>
  74. <mesh filename="package://drz_telemax_description/meshes/battery.dae" scale="0.001 0.001 0.001"/>
  75. </geometry>
  76. </visual>
  77. <collision>
  78. <origin rpy="0 0 0" xyz="0 0 0.105"/>
  79. <geometry>
  80. <box size="0.65 0.27 0.2"/>
  81. </geometry>
  82. </collision>
  83. </link>
  84. <joint name="flipper_front_left_joint" type="revolute">
  85. <origin rpy="0 0 0" xyz="0.205 0.17 0.085"/>
  86. <!-- <origin xyz="${0.205*front} 0 0.085"/> -->
  87. <axis xyz="0 1 0"/>
  88. <anchor xyz="0 0 0"/>
  89. <!-- <limit upper="${80.0/180.0*M_PI}" lower="${-M_PI/2}" velocity="0.262745098" effort="1000"/>-->
  90. <limit effort="1000" lower="-1.57079632679" upper="1.57079632679" velocity="0.209439510239"/>
  91. <parent link="chassis_link"/>
  92. <child link="flipper_front_left_link"/>
  93. </joint>
  94. <link name="flipper_front_left_link">
  95. <inertial>
  96. <origin rpy="0 0 0" xyz="0.2485 0 0"/>
  97. <mass value="5"/>
  98. <inertia ixx="0.0138266666667" ixy="0.0" ixz="0.0" iyy="0.115247083333" iyz="0.0" izz="0.104420416667"/>
  99. </inertial>
  100. <visual>
  101. <origin rpy="1.57079632679 3.14159265359 3.14159265359" xyz="0 -0.17 0"/>
  102. <geometry>
  103. <mesh filename="package://drz_telemax_description/meshes/flipper.dae" scale="0.001 0.001 0.001"/>
  104. </geometry>
  105. </visual>
  106. <!-- *** Collision geometry ***-->
  107. <!-- Main wheel -->
  108. <collision>
  109. <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
  110. <geometry>
  111. <cylinder length="0.06" radius="0.136"/>
  112. </geometry>
  113. </collision>
  114. <!-- Tip wheel -->
  115. <collision>
  116. <origin rpy="1.57079632679 0 0" xyz="0.497 0 0.051"/>
  117. <geometry>
  118. <cylinder length="0.06" radius="0.086"/>
  119. </geometry>
  120. </collision>
  121. <!-- Small wheel -->
  122. <collision>
  123. <origin rpy="1.57079632679 0 0" xyz="0.165 0 -0.0763"/>
  124. <geometry>
  125. <cylinder length="0.06" radius="0.0862"/>
  126. </geometry>
  127. </collision>
  128. <!-- Track between main wheel and small wheel -->
  129. <collision>
  130. <origin rpy="0 0.15 0" xyz="0.0674 0 -0.139"/>
  131. <geometry>
  132. <box size="0.174 0.06 0.0187"/>
  133. </geometry>
  134. </collision>
  135. <!-- Track between small wheel and tip wheel -->
  136. <collision>
  137. <origin rpy="0 -0.364 0" xyz="0.358 0 -0.085"/>
  138. <geometry>
  139. <box size="0.355 0.06 0.0187"/>
  140. </geometry>
  141. </collision>
  142. <!-- Track on top of the flipper -->
  143. <collision>
  144. <origin rpy="0 0 0" xyz="0.25 0 0.12665"/>
  145. <geometry>
  146. <box size="0.5 0.06 0.0187"/>
  147. </geometry>
  148. </collision>
  149. </link>
  150. <!--Needed for gazebo-->
  151. <transmission name="flipper_front_left_joint_transmission">
  152. <type>transmission_interface/SimpleTransmission</type>
  153. <joint name="flipper_front_left_joint">
  154. <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
  155. </joint>
  156. <actuator name="flipper_front_left_joint_motor">
  157. <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
  158. <mechanicalReduction>1</mechanicalReduction>
  159. </actuator>
  160. </transmission>
  161. <joint name="flipper_front_right_joint" type="revolute">
  162. <origin rpy="0 0 0" xyz="0.205 -0.17 0.085"/>
  163. <!-- <origin xyz="${0.205*front} 0 0.085"/> -->
  164. <axis xyz="0 1 0"/>
  165. <anchor xyz="0 0 0"/>
  166. <!-- <limit upper="${80.0/180.0*M_PI}" lower="${-M_PI/2}" velocity="0.262745098" effort="1000"/>-->
  167. <limit effort="1000" lower="-1.57079632679" upper="1.57079632679" velocity="0.209439510239"/>
  168. <parent link="chassis_link"/>
  169. <child link="flipper_front_right_link"/>
  170. </joint>
  171. <link name="flipper_front_right_link">
  172. <inertial>
  173. <origin rpy="0 0 0" xyz="0.2485 0 0"/>
  174. <mass value="5"/>
  175. <inertia ixx="0.0138266666667" ixy="0.0" ixz="0.0" iyy="0.115247083333" iyz="0.0" izz="0.104420416667"/>
  176. </inertial>
  177. <visual>
  178. <origin rpy="1.57079632679 3.14159265359 3.14159265359" xyz="0 0.17 0"/>
  179. <geometry>
  180. <mesh filename="package://drz_telemax_description/meshes/flipper.dae" scale="0.001 0.001 -0.001"/>
  181. </geometry>
  182. </visual>
  183. <!-- *** Collision geometry ***-->
  184. <!-- Main wheel -->
  185. <collision>
  186. <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
  187. <geometry>
  188. <cylinder length="0.06" radius="0.136"/>
  189. </geometry>
  190. </collision>
  191. <!-- Tip wheel -->
  192. <collision>
  193. <origin rpy="1.57079632679 0 0" xyz="0.497 0 0.051"/>
  194. <geometry>
  195. <cylinder length="0.06" radius="0.086"/>
  196. </geometry>
  197. </collision>
  198. <!-- Small wheel -->
  199. <collision>
  200. <origin rpy="1.57079632679 0 0" xyz="0.165 0 -0.0763"/>
  201. <geometry>
  202. <cylinder length="0.06" radius="0.0862"/>
  203. </geometry>
  204. </collision>
  205. <!-- Track between main wheel and small wheel -->
  206. <collision>
  207. <origin rpy="0 0.15 0" xyz="0.0674 0 -0.139"/>
  208. <geometry>
  209. <box size="0.174 0.06 0.0187"/>
  210. </geometry>
  211. </collision>
  212. <!-- Track between small wheel and tip wheel -->
  213. <collision>
  214. <origin rpy="0 -0.364 0" xyz="0.358 0 -0.085"/>
  215. <geometry>
  216. <box size="0.355 0.06 0.0187"/>
  217. </geometry>
  218. </collision>
  219. <!-- Track on top of the flipper -->
  220. <collision>
  221. <origin rpy="0 0 0" xyz="0.25 0 0.12665"/>
  222. <geometry>
  223. <box size="0.5 0.06 0.0187"/>
  224. </geometry>
  225. </collision>
  226. </link>
  227. <!--Needed for gazebo-->
  228. <transmission name="flipper_front_right_joint_transmission">
  229. <type>transmission_interface/SimpleTransmission</type>
  230. <joint name="flipper_front_right_joint">
  231. <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
  232. </joint>
  233. <actuator name="flipper_front_right_joint_motor">
  234. <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
  235. <mechanicalReduction>1</mechanicalReduction>
  236. </actuator>
  237. </transmission>
  238. <joint name="flipper_back_left_joint" type="revolute">
  239. <origin rpy="0 0 3.14159265359" xyz="-0.205 0.17 0.085"/>
  240. <!-- <origin xyz="${0.205*front} 0 0.085"/> -->
  241. <axis xyz="0 -1 0"/>
  242. <anchor xyz="0 0 0"/>
  243. <!-- <limit upper="${80.0/180.0*M_PI}" lower="${-M_PI/2}" velocity="0.262745098" effort="1000"/>-->
  244. <limit effort="1000" lower="-1.57079632679" upper="1.57079632679" velocity="0.209439510239"/>
  245. <parent link="chassis_link"/>
  246. <child link="flipper_back_left_link"/>
  247. </joint>
  248. <link name="flipper_back_left_link">
  249. <inertial>
  250. <origin rpy="0 0 0" xyz="0.2485 0 0"/>
  251. <mass value="5"/>
  252. <inertia ixx="0.0138266666667" ixy="0.0" ixz="0.0" iyy="0.115247083333" iyz="0.0" izz="0.104420416667"/>
  253. </inertial>
  254. <visual>
  255. <origin rpy="1.57079632679 3.14159265359 3.14159265359" xyz="0 0.17 0"/>
  256. <geometry>
  257. <mesh filename="package://drz_telemax_description/meshes/flipper.dae" scale="0.001 0.001 -0.001"/>
  258. </geometry>
  259. </visual>
  260. <!-- *** Collision geometry ***-->
  261. <!-- Main wheel -->
  262. <collision>
  263. <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
  264. <geometry>
  265. <cylinder length="0.06" radius="0.136"/>
  266. </geometry>
  267. </collision>
  268. <!-- Tip wheel -->
  269. <collision>
  270. <origin rpy="1.57079632679 0 0" xyz="0.497 0 0.051"/>
  271. <geometry>
  272. <cylinder length="0.06" radius="0.086"/>
  273. </geometry>
  274. </collision>
  275. <!-- Small wheel -->
  276. <collision>
  277. <origin rpy="1.57079632679 0 0" xyz="0.165 0 -0.0763"/>
  278. <geometry>
  279. <cylinder length="0.06" radius="0.0862"/>
  280. </geometry>
  281. </collision>
  282. <!-- Track between main wheel and small wheel -->
  283. <collision>
  284. <origin rpy="0 0.15 0" xyz="0.0674 0 -0.139"/>
  285. <geometry>
  286. <box size="0.174 0.06 0.0187"/>
  287. </geometry>
  288. </collision>
  289. <!-- Track between small wheel and tip wheel -->
  290. <collision>
  291. <origin rpy="0 -0.364 0" xyz="0.358 0 -0.085"/>
  292. <geometry>
  293. <box size="0.355 0.06 0.0187"/>
  294. </geometry>
  295. </collision>
  296. <!-- Track on top of the flipper -->
  297. <collision>
  298. <origin rpy="0 0 0" xyz="0.25 0 0.12665"/>
  299. <geometry>
  300. <box size="0.5 0.06 0.0187"/>
  301. </geometry>
  302. </collision>
  303. </link>
  304. <!--Needed for gazebo-->
  305. <transmission name="flipper_back_left_joint_transmission">
  306. <type>transmission_interface/SimpleTransmission</type>
  307. <joint name="flipper_back_left_joint">
  308. <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
  309. </joint>
  310. <actuator name="flipper_back_left_joint_motor">
  311. <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
  312. <mechanicalReduction>1</mechanicalReduction>
  313. </actuator>
  314. </transmission>
  315. <joint name="flipper_back_right_joint" type="revolute">
  316. <origin rpy="0 0 3.14159265359" xyz="-0.205 -0.17 0.085"/>
  317. <!-- <origin xyz="${0.205*front} 0 0.085"/> -->
  318. <axis xyz="0 -1 0"/>
  319. <anchor xyz="0 0 0"/>
  320. <!-- <limit upper="${80.0/180.0*M_PI}" lower="${-M_PI/2}" velocity="0.262745098" effort="1000"/>-->
  321. <limit effort="1000" lower="-1.57079632679" upper="1.57079632679" velocity="0.209439510239"/>
  322. <parent link="chassis_link"/>
  323. <child link="flipper_back_right_link"/>
  324. </joint>
  325. <link name="flipper_back_right_link">
  326. <inertial>
  327. <origin rpy="0 0 0" xyz="0.2485 0 0"/>
  328. <mass value="5"/>
  329. <inertia ixx="0.0138266666667" ixy="0.0" ixz="0.0" iyy="0.115247083333" iyz="0.0" izz="0.104420416667"/>
  330. </inertial>
  331. <visual>
  332. <origin rpy="1.57079632679 3.14159265359 3.14159265359" xyz="0 -0.17 0"/>
  333. <geometry>
  334. <mesh filename="package://drz_telemax_description/meshes/flipper.dae" scale="0.001 0.001 0.001"/>
  335. </geometry>
  336. </visual>
  337. <!-- *** Collision geometry ***-->
  338. <!-- Main wheel -->
  339. <collision>
  340. <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
  341. <geometry>
  342. <cylinder length="0.06" radius="0.136"/>
  343. </geometry>
  344. </collision>
  345. <!-- Tip wheel -->
  346. <collision>
  347. <origin rpy="1.57079632679 0 0" xyz="0.497 0 0.051"/>
  348. <geometry>
  349. <cylinder length="0.06" radius="0.086"/>
  350. </geometry>
  351. </collision>
  352. <!-- Small wheel -->
  353. <collision>
  354. <origin rpy="1.57079632679 0 0" xyz="0.165 0 -0.0763"/>
  355. <geometry>
  356. <cylinder length="0.06" radius="0.0862"/>
  357. </geometry>
  358. </collision>
  359. <!-- Track between main wheel and small wheel -->
  360. <collision>
  361. <origin rpy="0 0.15 0" xyz="0.0674 0 -0.139"/>
  362. <geometry>
  363. <box size="0.174 0.06 0.0187"/>
  364. </geometry>
  365. </collision>
  366. <!-- Track between small wheel and tip wheel -->
  367. <collision>
  368. <origin rpy="0 -0.364 0" xyz="0.358 0 -0.085"/>
  369. <geometry>
  370. <box size="0.355 0.06 0.0187"/>
  371. </geometry>
  372. </collision>
  373. <!-- Track on top of the flipper -->
  374. <collision>
  375. <origin rpy="0 0 0" xyz="0.25 0 0.12665"/>
  376. <geometry>
  377. <box size="0.5 0.06 0.0187"/>
  378. </geometry>
  379. </collision>
  380. </link>
  381. <!--Needed for gazebo-->
  382. <transmission name="flipper_back_right_joint_transmission">
  383. <type>transmission_interface/SimpleTransmission</type>
  384. <joint name="flipper_back_right_joint">
  385. <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
  386. </joint>
  387. <actuator name="flipper_back_right_joint_motor">
  388. <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
  389. <mechanicalReduction>1</mechanicalReduction>
  390. </actuator>
  391. </transmission>
  392. <!-- Base link gazebo properties TODO should this be chassis link?-->
  393. <!-- <gazebo reference="base_link">
  394. <mu1>0.0</mu1>
  395. <mu2>0.0</mu2>
  396. <kp>1000000.0</kp>
  397. <kd>100.0</kd>
  398. <minDepth>0.001</minDepth>
  399. <maxVel>1.0</maxVel>
  400. </gazebo>-->
  401. <gazebo>
  402. <!-- Publish ground truth -->
  403. <plugin filename="libgazebo_ros_p3d.so" name="p3d_base_controller">
  404. <alwaysOn>true</alwaysOn>
  405. <updateRate>50.0</updateRate>
  406. <bodyName>base_link</bodyName>
  407. <topicName>ground_truth/state</topicName>
  408. <gaussianNoise>0.01</gaussianNoise>
  409. <frameName>world</frameName>
  410. <xyzOffsets>0 0 0</xyzOffsets>
  411. <rpyOffsets>0 0 0</rpyOffsets>
  412. </plugin>
  413. <!-- IMU plugin -->
  414. <plugin filename="libhector_gazebo_ros_imu.so" name="imu_controller">
  415. <alwaysOn>true</alwaysOn>
  416. <updateRate>50.0</updateRate>
  417. <bodyName>base_link</bodyName>
  418. <topicName>imu/data</topicName>
  419. <accelDrift>0.0 0.0 0.0</accelDrift>
  420. <accelGaussianNoise>0.1 0.1 0.1</accelGaussianNoise>
  421. <rateDrift>0.0 0.0 0.0</rateDrift>
  422. <rateGaussianNoise>0.05 0.05 0.05</rateGaussianNoise>
  423. <headingDrift>0.0</headingDrift>
  424. <headingGaussianNoise>0.05</headingGaussianNoise>
  425. </plugin>
  426. </gazebo>
  427. <gazebo reference="main_track_left_fixed_joint">
  428. <preserveFixedJoint>true</preserveFixedJoint>
  429. </gazebo>
  430. <gazebo reference="main_track_right_fixed_joint">
  431. <preserveFixedJoint>true</preserveFixedJoint>
  432. </gazebo>
  433. <gazebo reference="flipper_front_left_link">
  434. <!-- <mu1>0.0</mu1>
  435. <mu2>0.0</mu2>
  436. <kp>1000000.0</kp>
  437. <kd>100.0</kd>
  438. <minDepth>0.001</minDepth>
  439. <maxVel>1.0</maxVel>-->
  440. </gazebo>
  441. <gazebo reference="flipper_back_left_link">
  442. <!-- <mu1>0.0</mu1>
  443. <mu2>0.0</mu2>
  444. <kp>1000000.0</kp>
  445. <kd>100.0</kd>
  446. <minDepth>0.001</minDepth>
  447. <maxVel>1.0</maxVel>-->
  448. </gazebo>
  449. <gazebo reference="flipper_front_right_link">
  450. <!-- <mu1>0.0</mu1>
  451. <mu2>0.0</mu2>
  452. <kp>1000000.0</kp>
  453. <kd>100.0</kd>
  454. <minDepth>0.001</minDepth>
  455. <maxVel>1.0</maxVel>-->
  456. </gazebo>
  457. <gazebo reference="flipper_back_right_link">
  458. <!-- <mu1>0.0</mu1>
  459. <mu2>0.0</mu2>
  460. <kp>1000000.0</kp>
  461. <kd>100.0</kd>
  462. <minDepth>0.001</minDepth>
  463. <maxVel>1.0</maxVel>-->
  464. </gazebo>
  465. <gazebo>
  466. <plugin filename="libgazebo_ros_tracked_vehicle_plugin.so" name="multi_tracked_vehicle">
  467. <command_topic>/cmd_vel_raw</command_topic>
  468. <body>base_link</body>
  469. <left_track0>flipper_front_left_link</left_track0>
  470. <left_track1>flipper_back_left_link</left_track1>
  471. <right_track0>flipper_front_right_link</right_track0>
  472. <right_track1>flipper_back_right_link</right_track1>
  473. <track_mu>0.7</track_mu>
  474. <track_mu2>150</track_mu2>
  475. <tracks_separation>0.34</tracks_separation>
  476. <steering_efficiency>0.5</steering_efficiency>
  477. <max_linear_speed>1.0</max_linear_speed>
  478. <max_angular_speed>1.0</max_angular_speed>
  479. </plugin>
  480. <plugin filename="libkeys_to_cmd_vel_plugin.so" name="keyboard_control">
  481. <cmd_vel_topic>~/robot_description_gazebo/cmd_vel</cmd_vel_topic>
  482. </plugin>
  483. </gazebo>
  484. <gazebo>
  485. <!-- Gazebo ros control -->
  486. <plugin filename="libgazebo_ros_control_select_joints.so" name="gazebo_ros_control_select_joints">
  487. <robotNamespace>telemax_control</robotNamespace>
  488. <joints>arm_joint_0 arm_joint_1 arm_joint_2 arm_joint_3 arm_joint_4 arm_joint_5 gripper_joint flipper_front_left_joint flipper_front_right_joint flipper_back_left_joint flipper_back_right_joint</joints>
  489. </plugin>
  490. </gazebo>
  491. <joint name="manipulator_base_joint" type="fixed">
  492. <origin rpy="0 0 0" xyz="0.225 0.0 0.24125"/>
  493. <parent link="base_link"/>
  494. <child link="manipulator_base_link"/>
  495. </joint>
  496. <link name="manipulator_base_link">
  497. <inertial>
  498. <origin rpy="0 0 0" xyz="0 0 0.0"/>
  499. <mass value="1"/>
  500. <inertia ixx="6.66666666667e-05" ixy="0.0" ixz="0.0" iyy="6.66666666667e-05" iyz="0.0" izz="6.66666666667e-05"/>
  501. </inertial>
  502. <visual>
  503. <geometry>
  504. <mesh filename="package://drz_telemax_description/meshes/manipulator_base_link.dae" scale="0.001 0.001 0.001"/>
  505. </geometry>
  506. </visual>
  507. <collision>
  508. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  509. <geometry>
  510. <cylinder length="0.02" radius="0.1"/>
  511. </geometry>
  512. </collision>
  513. </link>
  514. <joint name="arm_joint_0" type="revolute">
  515. <parent link="manipulator_base_link"/>
  516. <child link="arm_link_0"/>
  517. <origin rpy="0 0 0" xyz="0 0 0"/>
  518. <axis xyz="0 0 1"/>
  519. <limit effort="10000.0" lower="-3.66519142919" upper="3.66519142919" velocity="0.628318530718"/>
  520. </joint>
  521. <link name="arm_link_0">
  522. <inertial>
  523. <origin rpy="0 0 0" xyz="0.004 0.02135 0.126"/>
  524. <mass value="3"/>
  525. <inertia ixx="0.0181" ixy="0.0" ixz="0.0" iyy="0.023725" iyz="0.0" izz="0.025625"/>
  526. </inertial>
  527. <visual>
  528. <geometry>
  529. <mesh filename="package://drz_telemax_description/meshes/arm_link_0.dae" scale="0.001 0.001 0.001"/>
  530. </geometry>
  531. </visual>
  532. <!-- Tower body -->
  533. <collision>
  534. <origin rpy="0 0 0" xyz="0.01 0.025 0.165"/>
  535. <geometry>
  536. <box size="0.25 0.2 0.18"/>
  537. </geometry>
  538. </collision>
  539. <!-- Tower cylinder -->
  540. <collision>
  541. <origin rpy="0 0 0" xyz="0.0 0.0 0.03"/>
  542. <geometry>
  543. <cylinder length="0.09" radius="0.075"/>
  544. </geometry>
  545. </collision>
  546. <!-- Ring at tower base -->
  547. <collision>
  548. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  549. <geometry>
  550. <cylinder length="0.02" radius="0.1"/>
  551. </geometry>
  552. </collision>
  553. <!-- Antenna 1 -->
  554. <collision>
  555. <origin rpy="0 0 0" xyz="-0.115 0.09625 0.365"/>
  556. <geometry>
  557. <cylinder length="0.22" radius="0.01"/>
  558. </geometry>
  559. </collision>
  560. <!-- Antenna 2 -->
  561. <collision>
  562. <origin rpy="0 0 0" xyz="0.015 0.125 0.365"/>
  563. <geometry>
  564. <cylinder length="0.22" radius="0.01"/>
  565. </geometry>
  566. </collision>
  567. </link>
  568. <joint name="arm_joint_1" type="revolute">
  569. <parent link="arm_link_0"/>
  570. <child link="arm_link_1"/>
  571. <origin rpy="0 0 0" xyz="0.06 -0.0815 0.14"/>
  572. <axis xyz="0 1 0"/>
  573. <limit effort="10000.0" lower="-2.72271363311" upper="1.0471975512" velocity="0.314159265359"/>
  574. </joint>
  575. <link name="arm_link_1">
  576. <!-- <inertial>
  577. <origin xyz="${-0.066 + (0.066+0.089)/2} 0 0" rpy="0 0 0"/>
  578. <mass value="1.0" />
  579. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
  580. </inertial>-->
  581. <inertial>
  582. <origin rpy="0 0 0" xyz="0.33 0 0"/>
  583. <mass value="5"/>
  584. <inertia ixx="0.00533333333333" ixy="0.0" ixz="0.0" iyy="0.269333333333" iyz="0.0" izz="0.269333333333"/>
  585. </inertial>
  586. <visual>
  587. <geometry>
  588. <mesh filename="package://drz_telemax_description/meshes/arm_link_1.dae" scale="0.001 0.001 0.001"/>
  589. </geometry>
  590. </visual>
  591. <collision>
  592. <origin rpy="0 0 0" xyz="0.01 -0.005 0"/>
  593. <geometry>
  594. <box size="0.16 0.08 0.110"/>
  595. </geometry>
  596. </collision>
  597. <collision>
  598. <origin rpy="0 0 0" xyz="0.26 -0.005 0"/>
  599. <geometry>
  600. <box size="0.36 0.08 0.08"/>
  601. </geometry>
  602. </collision>
  603. <collision>
  604. <origin rpy="0 0 0" xyz="0.56 -0.02 0"/>
  605. <geometry>
  606. <box size="0.35 0.085 0.13"/>
  607. </geometry>
  608. </collision>
  609. </link>
  610. <joint name="arm_joint_2" type="revolute">
  611. <parent link="arm_link_1"/>
  612. <child link="arm_link_2"/>
  613. <origin rpy="0 0 0" xyz="0.67 0.081 0.0"/>
  614. <axis xyz="0 1 0"/>
  615. <limit effort="10000.0" lower="-2.96705972839" upper="2.96705972839" velocity="0.628318530718"/>
  616. </joint>
  617. <link name="arm_link_2">
  618. <!-- <inertial>
  619. <origin xyz="${-0.04 + (0.04+0.04+0.1246)/2} ${0.0634 - (0.0634+0.12-0.08)/2} ${-0.04 + (0.04+0.05)/2}" rpy="0 0 0"/>
  620. <mass value="1.0" />
  621. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
  622. </inertial>-->
  623. <inertial>
  624. <origin rpy="0 0 0" xyz="0.01 0.01 0.01"/>
  625. <mass value="1"/>
  626. <inertia ixx="0.00350833333333" ixy="0.0" ixz="0.0" iyy="0.00375" iyz="0.0" izz="0.00350833333333"/>
  627. </inertial>
  628. <visual>
  629. <geometry>
  630. <mesh filename="package://drz_telemax_description/meshes/arm_link_2.dae" scale="0.001 0.001 0.001"/>
  631. </geometry>
  632. </visual>
  633. <collision>
  634. <origin rpy="0 0 0" xyz="0.01 0.01 0.01"/>
  635. <geometry>
  636. <box size="0.15 0.14 0.15"/>
  637. </geometry>
  638. </collision>
  639. <collision>
  640. <origin rpy="0 0 0" xyz="0.11 0.0 0.0"/>
  641. <geometry>
  642. <box size="0.05 0.09 0.09"/>
  643. </geometry>
  644. </collision>
  645. </link>
  646. <joint name="arm_joint_3" type="revolute">
  647. <parent link="arm_link_2"/>
  648. <child link="arm_link_3"/>
  649. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  650. <axis xyz="1 0 0"/>
  651. <limit effort="10000.0" lower="-3.66519142919" upper="3.66519142919" velocity="1.25663706144"/>
  652. </joint>
  653. <link name="arm_link_3">
  654. <!-- <inertial>
  655. <origin xyz="${0.494/2} ${0.0523 - 0.1195/2} 0" rpy="0 0 0"/>
  656. <mass value="1.0" />
  657. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
  658. </inertial>-->
  659. <inertial>
  660. <origin rpy="0 0 0" xyz="0.3 0.0 0.0"/>
  661. <mass value="3"/>
  662. <inertia ixx="0.00405" ixy="0.0" ixz="0.0" iyy="0.05265" iyz="0.0" izz="0.05265"/>
  663. </inertial>
  664. <visual>
  665. <geometry>
  666. <mesh filename="package://drz_telemax_description/meshes/arm_link_3.dae" scale="0.001 0.001 0.001"/>
  667. </geometry>
  668. </visual>
  669. <collision>
  670. <origin rpy="0 0 0" xyz="0.3 0.0 0.0"/>
  671. <geometry>
  672. <box size="0.35 0.09 0.09"/>
  673. </geometry>
  674. </collision>
  675. <collision>
  676. <origin rpy="0 0 0" xyz="0.53 0.055 0"/>
  677. <geometry>
  678. <box size="0.25 0.045 0.09"/>
  679. </geometry>
  680. </collision>
  681. <collision>
  682. <origin rpy="0 0 0" xyz="0.46 0.01 0"/>
  683. <geometry>
  684. <box size="0.13 0.13 0.09"/>
  685. </geometry>
  686. </collision>
  687. </link>
  688. <joint name="arm_joint_4" type="revolute">
  689. <parent link="arm_link_3"/>
  690. <child link="arm_link_4"/>
  691. <origin rpy="0 0 0" xyz="0.615 0.0 0.0"/>
  692. <axis xyz="0 1 0"/>
  693. <limit effort="10000.0" lower="-2.26892802759" upper="2.26892802759" velocity="1.36135681656"/>
  694. </joint>
  695. <link name="arm_link_4">
  696. <!-- <inertial>
  697. <origin xyz="${-0.059 + 0.168/2} ${-0.046 + 0.076/2.0} ${-0.0367 + (0.0513+0.0367)/2}" rpy="0 0 0"/>
  698. <mass value="1.0" />
  699. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
  700. </inertial>-->
  701. <inertial>
  702. <origin rpy="0 0 0" xyz="0.025 -0.01 0.005"/>
  703. <mass value="1"/>
  704. <inertia ixx="0.00150833333333" ixy="0.0" ixz="0.0" iyy="0.00435" iyz="0.0" izz="0.00450833333333"/>
  705. </inertial>
  706. <visual>
  707. <geometry>
  708. <mesh filename="package://drz_telemax_description/meshes/arm_link_4.dae" scale="0.001 0.001 0.001"/>
  709. </geometry>
  710. </visual>
  711. <collision>
  712. <origin rpy="0 0 0" xyz="0.025 -0.01 0.005"/>
  713. <geometry>
  714. <box size="0.21 0.1 0.09"/>
  715. </geometry>
  716. </collision>
  717. <collision>
  718. <origin rpy="0 0 0" xyz="0.0625 -0.00125 0.055"/>
  719. <geometry>
  720. <cylinder length="0.02" radius="0.03"/>
  721. </geometry>
  722. </collision>
  723. </link>
  724. <joint name="arm_joint_5" type="continuous">
  725. <parent link="arm_link_4"/>
  726. <child link="arm_link_5"/>
  727. <origin rpy="0 0 0" xyz="0.12887 0.0 0.00065"/>
  728. <axis xyz="1 0 0"/>
  729. <limit effort="10000.0" velocity="1.29154364648"/>
  730. </joint>
  731. <link name="arm_link_5">
  732. <!-- <inertial>
  733. <origin xyz="${0.063/2} 0 ${-0.0525 + (0.0184+0.0525)/2}" rpy="0 0 0"/>
  734. <mass value="1.0" />
  735. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
  736. </inertial>-->
  737. <inertial>
  738. <origin rpy="0 0 0" xyz="0.036 0.0 0.0"/>
  739. <mass value="0.5"/>
  740. <inertia ixx="0.000901041666667" ixy="0.0" ixz="0.0" iyy="0.00031875" iyz="0.0" izz="0.00105104166667"/>
  741. </inertial>
  742. <visual>
  743. <geometry>
  744. <mesh filename="package://drz_telemax_description/meshes/arm_link_5.dae" scale="0.001 0.001 0.001"/>
  745. </geometry>
  746. </visual>
  747. <collision>
  748. <origin rpy="0 0 0" xyz="0.036 0.0 0.0"/>
  749. <geometry>
  750. <box size="0.075 0.14 0.045"/>
  751. </geometry>
  752. </collision>
  753. <collision>
  754. <origin rpy="0 0 0" xyz="0.03 0.0 0.035"/>
  755. <geometry>
  756. <box size="0.045 0.045 0.045"/>
  757. </geometry>
  758. </collision>
  759. </link>
  760. <!-- Gripper -->
  761. <joint name="gripper_joint" type="revolute">
  762. <origin rpy="0 0 0" xyz="0 0 0"/>
  763. <axis xyz="0 0 1"/>
  764. <limit effort="1000" lower="0" upper="0.2" velocity="0.02"/>
  765. <parent link="arm_link_5"/>
  766. <child link="gripper_servo_link"/>
  767. </joint>
  768. <link name="gripper_servo_link">
  769. <inertial>
  770. <origin rpy="0 0 0" xyz="0 0 0"/>
  771. <mass value="0.01"/>
  772. <inertia ixx="4.16666666667e-06" ixy="0.0" ixz="0.0" iyy="4.16666666667e-06" iyz="0.0" izz="4.16666666667e-06"/>
  773. </inertial>
  774. <!-- <visual>
  775. <origin xyz="0 0.0 0.0" rpy="0.0 0.0 0.0" />
  776. <geometry>
  777. <cylinder length="0.01" radius="0.01" />
  778. </geometry>
  779. </visual>
  780. <collision>
  781. <origin xyz="0 0.0 0.0" rpy="0.0 0.0 0.0" />
  782. <geometry>
  783. <cylinder length="0.01" radius="0.01" />
  784. </geometry>
  785. </collision>-->
  786. </link>
  787. <joint name="left_finger_middle_joint" type="revolute">
  788. <origin rpy="0 0 0" xyz="0.035 0.039 0"/>
  789. <parent link="arm_link_5"/>
  790. <child link="left_finger_middle_link"/>
  791. <axis xyz="0 0 1"/>
  792. <mimic joint="gripper_joint" multiplier="5.1" offset="-0.12"/>
  793. <limit effort="1000" lower="-0.12" upper="1.02" velocity="1"/>
  794. </joint>
  795. <link name="left_finger_middle_link">
  796. <!-- <inertial>
  797. <origin xyz="${-0.04 + (0.04+0.04+0.1246)/2} ${0.0634 - (0.0634+0.12-0.08)/2} ${-0.04 + (0.04+0.05)/2}" rpy="0 0 0"/>
  798. <mass value="1.0" />
  799. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
  800. </inertial>-->
  801. <inertial>
  802. <origin rpy="0 0 0" xyz="0.05 0.01 0.0"/>
  803. <mass value="0.5"/>
  804. <inertia ixx="9.27083333333e-05" ixy="0.0" ixz="0.0" iyy="0.000842708333333" iyz="0.0" izz="0.000883333333333"/>
  805. </inertial>
  806. <visual>
  807. <geometry>
  808. <mesh filename="package://drz_telemax_description/meshes/finger_middle_link.dae" scale="0.001 0.001 0.001"/>
  809. </geometry>
  810. </visual>
  811. <collision>
  812. <origin rpy="0 0 0" xyz="0.05 0.01 0.0"/>
  813. <geometry>
  814. <box size="0.14 0.04 0.025"/>
  815. </geometry>
  816. </collision>
  817. </link>
  818. <joint name="left_finger_end_joint" type="revolute">
  819. <parent link="left_finger_middle_link"/>
  820. <child link="left_finger_end_link"/>
  821. <origin rpy="0 0 0" xyz="0.110 0.0 0.0"/>
  822. <axis xyz="0 0 1"/>
  823. <mimic joint="gripper_joint" multiplier="-5.1" offset="0.12"/>
  824. <limit effort="1000" lower="-1.02" upper="0.12" velocity="1"/>
  825. </joint>
  826. <link name="left_finger_end_link">
  827. <!-- <inertial>
  828. <origin xyz="${-0.04 + (0.04+0.04+0.1246)/2} ${0.0634 - (0.0634+0.12-0.08)/2} ${-0.04 + (0.04+0.05)/2}" rpy="0 0 0"/>
  829. <mass value="1.0" />
  830. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
  831. </inertial>-->
  832. <inertial>
  833. <origin rpy="0 0 0" xyz="0.05 -0.01225 0.0"/>
  834. <mass value="0.5"/>
  835. <inertia ixx="6.90104166667e-05" ixy="0.0" ixz="0.0" iyy="0.000298177083333" iyz="0.0" izz="0.000304166666667"/>
  836. </inertial>
  837. <visual>
  838. <geometry>
  839. <mesh filename="package://drz_telemax_description/meshes/finger_end_link.dae" scale="0.001 0.001 0.001"/>
  840. </geometry>
  841. </visual>
  842. <collision>
  843. <origin rpy="0 0 0" xyz="0.05 -0.01225 0.0"/>
  844. <geometry>
  845. <box size="0.08 0.03 0.0275"/>
  846. </geometry>
  847. </collision>
  848. <collision>
  849. <origin rpy="0 0 -0.785398163397" xyz="0.0 0.0 0.0"/>
  850. <geometry>
  851. <box size="0.06 0.03 0.0275"/>
  852. </geometry>
  853. </collision>
  854. </link>
  855. <gazebo>
  856. <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_left_finger_middle_joint">
  857. <joint>gripper_joint</joint>
  858. <mimicJoint>left_finger_middle_joint</mimicJoint>
  859. <multiplier>5.1</multiplier>
  860. <offset>-0.12</offset>
  861. <maxEffort>4</maxEffort>
  862. <hasPID/>
  863. </plugin>
  864. <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_left_finger_end_joint">
  865. <joint>gripper_joint</joint>
  866. <mimicJoint>left_finger_end_joint</mimicJoint>
  867. <multiplier>-5.1</multiplier>
  868. <offset>0.12</offset>
  869. <maxEffort>4</maxEffort>
  870. <hasPID/>
  871. </plugin>
  872. </gazebo>
  873. <joint name="right_finger_middle_joint" type="revolute">
  874. <origin rpy="3.14159265359 0 0" xyz="0.035 -0.039 0"/>
  875. <parent link="arm_link_5"/>
  876. <child link="right_finger_middle_link"/>
  877. <axis xyz="0 0 1"/>
  878. <mimic joint="gripper_joint" multiplier="5.1" offset="-0.12"/>
  879. <limit effort="1000" lower="-0.12" upper="1.02" velocity="1"/>
  880. </joint>
  881. <link name="right_finger_middle_link">
  882. <!-- <inertial>
  883. <origin xyz="${-0.04 + (0.04+0.04+0.1246)/2} ${0.0634 - (0.0634+0.12-0.08)/2} ${-0.04 + (0.04+0.05)/2}" rpy="0 0 0"/>
  884. <mass value="1.0" />
  885. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
  886. </inertial>-->
  887. <inertial>
  888. <origin rpy="0 0 0" xyz="0.05 0.01 0.0"/>
  889. <mass value="0.5"/>
  890. <inertia ixx="9.27083333333e-05" ixy="0.0" ixz="0.0" iyy="0.000842708333333" iyz="0.0" izz="0.000883333333333"/>
  891. </inertial>
  892. <visual>
  893. <geometry>
  894. <mesh filename="package://drz_telemax_description/meshes/finger_middle_link.dae" scale="0.001 0.001 0.001"/>
  895. </geometry>
  896. </visual>
  897. <collision>
  898. <origin rpy="0 0 0" xyz="0.05 0.01 0.0"/>
  899. <geometry>
  900. <box size="0.14 0.04 0.025"/>
  901. </geometry>
  902. </collision>
  903. </link>
  904. <joint name="right_finger_end_joint" type="revolute">
  905. <parent link="right_finger_middle_link"/>
  906. <child link="right_finger_end_link"/>
  907. <origin rpy="0 0 0" xyz="0.110 0.0 0.0"/>
  908. <axis xyz="0 0 1"/>
  909. <mimic joint="gripper_joint" multiplier="-5.1" offset="0.12"/>
  910. <limit effort="1000" lower="-1.02" upper="0.12" velocity="1"/>
  911. </joint>
  912. <link name="right_finger_end_link">
  913. <!-- <inertial>
  914. <origin xyz="${-0.04 + (0.04+0.04+0.1246)/2} ${0.0634 - (0.0634+0.12-0.08)/2} ${-0.04 + (0.04+0.05)/2}" rpy="0 0 0"/>
  915. <mass value="1.0" />
  916. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
  917. </inertial>-->
  918. <inertial>
  919. <origin rpy="0 0 0" xyz="0.05 -0.01225 0.0"/>
  920. <mass value="0.5"/>
  921. <inertia ixx="6.90104166667e-05" ixy="0.0" ixz="0.0" iyy="0.000298177083333" iyz="0.0" izz="0.000304166666667"/>
  922. </inertial>
  923. <visual>
  924. <geometry>
  925. <mesh filename="package://drz_telemax_description/meshes/finger_end_link.dae" scale="0.001 0.001 0.001"/>
  926. </geometry>
  927. </visual>
  928. <collision>
  929. <origin rpy="0 0 0" xyz="0.05 -0.01225 0.0"/>
  930. <geometry>
  931. <box size="0.08 0.03 0.0275"/>
  932. </geometry>
  933. </collision>
  934. <collision>
  935. <origin rpy="0 0 -0.785398163397" xyz="0.0 0.0 0.0"/>
  936. <geometry>
  937. <box size="0.06 0.03 0.0275"/>
  938. </geometry>
  939. </collision>
  940. </link>
  941. <gazebo>
  942. <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_right_finger_middle_joint">
  943. <joint>gripper_joint</joint>
  944. <mimicJoint>right_finger_middle_joint</mimicJoint>
  945. <multiplier>5.1</multiplier>
  946. <offset>-0.12</offset>
  947. <maxEffort>4</maxEffort>
  948. <hasPID/>
  949. </plugin>
  950. <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_right_finger_end_joint">
  951. <joint>gripper_joint</joint>
  952. <mimicJoint>right_finger_end_joint</mimicJoint>
  953. <multiplier>-5.1</multiplier>
  954. <offset>0.12</offset>
  955. <maxEffort>4</maxEffort>
  956. <hasPID/>
  957. </plugin>
  958. </gazebo>
  959. <!-- Virtual TCP link -->
  960. <joint name="gripper_tcp_joint" type="fixed">
  961. <origin rpy="0 0 0" xyz="0.234 0 0"/>
  962. <axis xyz="0 0 1"/>
  963. <parent link="arm_link_5"/>
  964. <child link="gripper_tcp_link"/>
  965. </joint>
  966. <link name="gripper_tcp_link">
  967. </link>
  968. <transmission name="arm_joint_0_joint_transmission">
  969. <type>transmission_interface/SimpleTransmission</type>
  970. <joint name="arm_joint_0">
  971. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  972. </joint>
  973. <actuator name="arm_joint_0_joint_motor">
  974. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  975. <mechanicalReduction>1</mechanicalReduction>
  976. </actuator>
  977. </transmission>
  978. <gazebo reference="arm_joint_0">
  979. <implicitSpringDamper>1</implicitSpringDamper>
  980. </gazebo>
  981. <transmission name="arm_joint_1_joint_transmission">
  982. <type>transmission_interface/SimpleTransmission</type>
  983. <joint name="arm_joint_1">
  984. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  985. </joint>
  986. <actuator name="arm_joint_1_joint_motor">
  987. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  988. <mechanicalReduction>1</mechanicalReduction>
  989. </actuator>
  990. </transmission>
  991. <gazebo reference="arm_joint_1">
  992. <implicitSpringDamper>1</implicitSpringDamper>
  993. </gazebo>
  994. <transmission name="arm_joint_2_joint_transmission">
  995. <type>transmission_interface/SimpleTransmission</type>
  996. <joint name="arm_joint_2">
  997. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  998. </joint>
  999. <actuator name="arm_joint_2_joint_motor">
  1000. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  1001. <mechanicalReduction>1</mechanicalReduction>
  1002. </actuator>
  1003. </transmission>
  1004. <gazebo reference="arm_joint_2">
  1005. <implicitSpringDamper>1</implicitSpringDamper>
  1006. </gazebo>
  1007. <transmission name="arm_joint_3_joint_transmission">
  1008. <type>transmission_interface/SimpleTransmission</type>
  1009. <joint name="arm_joint_3">
  1010. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  1011. </joint>
  1012. <actuator name="arm_joint_3_joint_motor">
  1013. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  1014. <mechanicalReduction>1</mechanicalReduction>
  1015. </actuator>
  1016. </transmission>
  1017. <gazebo reference="arm_joint_3">
  1018. <implicitSpringDamper>1</implicitSpringDamper>
  1019. </gazebo>
  1020. <transmission name="arm_joint_4_joint_transmission">
  1021. <type>transmission_interface/SimpleTransmission</type>
  1022. <joint name="arm_joint_4">
  1023. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  1024. </joint>
  1025. <actuator name="arm_joint_4_joint_motor">
  1026. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  1027. <mechanicalReduction>1</mechanicalReduction>
  1028. </actuator>
  1029. </transmission>
  1030. <gazebo reference="arm_joint_4">
  1031. <implicitSpringDamper>1</implicitSpringDamper>
  1032. </gazebo>
  1033. <transmission name="arm_joint_5_joint_transmission">
  1034. <type>transmission_interface/SimpleTransmission</type>
  1035. <joint name="arm_joint_5">
  1036. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  1037. </joint>
  1038. <actuator name="arm_joint_5_joint_motor">
  1039. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  1040. <mechanicalReduction>1</mechanicalReduction>
  1041. </actuator>
  1042. </transmission>
  1043. <gazebo reference="arm_joint_5">
  1044. <implicitSpringDamper>1</implicitSpringDamper>
  1045. </gazebo>
  1046. <transmission name="gripper_joint_joint_transmission">
  1047. <type>transmission_interface/SimpleTransmission</type>
  1048. <joint name="gripper_joint">
  1049. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  1050. </joint>
  1051. <actuator name="gripper_joint_joint_motor">
  1052. <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
  1053. <mechanicalReduction>1</mechanicalReduction>
  1054. </actuator>
  1055. </transmission>
  1056. <gazebo reference="gripper_joint">
  1057. <implicitSpringDamper>1</implicitSpringDamper>
  1058. </gazebo>
  1059. <joint name="autonomy_box_joint_fixed" type="fixed">
  1060. <origin rpy="0.0 0.0 0.0" xyz="-0.125 0.0 0.318"/>
  1061. <parent link="chassis_link"/>
  1062. <child link="autonomy_box_link"/>
  1063. </joint>
  1064. <link name="autonomy_box_link">
  1065. <origin rpy="0 0 0" xyz="0 0 0"/>
  1066. <visual>
  1067. <origin rpy="-1.57079632679 0 3.14159265359" xyz="0 0 -0.055"/>
  1068. <geometry>
  1069. <mesh filename="package://drz_telemax_description/meshes/autonomy_box.dae" scale="0.001 0.001 0.001"/>
  1070. </geometry>
  1071. </visual>
  1072. <collision>
  1073. <origin rpy="0 0 0" xyz="0 0 0"/>
  1074. <geometry>
  1075. <box size="0.353 0.24 0.11"/>
  1076. </geometry>
  1077. </collision>
  1078. </link>
  1079. <joint name="imu_link_joint" type="fixed">
  1080. <origin rpy="0 0 0" xyz="0.04 0.04 0.08"/>
  1081. <parent link="autonomy_box_link"/>
  1082. <child link="imu_link"/>
  1083. </joint>
  1084. <link name="imu_link">
  1085. </link>
  1086. <joint name="navigation_module_joint_fixed" type="fixed">
  1087. <origin rpy="0 0 0" xyz="-0.0265 0 0.0629"/>
  1088. <parent link="autonomy_box_link"/>
  1089. <child link="navigation_module_link"/>
  1090. </joint>
  1091. <link name="navigation_module_link">
  1092. <!-- Plate -->
  1093. <visual>
  1094. <origin rpy="0 0 0" xyz="0 0 0"/>
  1095. <geometry>
  1096. <box size="0.316 0.225 0.0062"/>
  1097. </geometry>
  1098. <material name="Gray"/>
  1099. </visual>
  1100. <collision>
  1101. <origin rpy="0 0 0" xyz="0 0 0"/>
  1102. <geometry>
  1103. <box size="0.316 0.225 0.0062"/>
  1104. </geometry>
  1105. <material name="Gray"/>
  1106. </collision>
  1107. <!-- Protection Vertical Profiles -->
  1108. <visual>
  1109. <origin rpy="0 0 0" xyz="-0.14 0.1025 0.1626"/>
  1110. <geometry>
  1111. <box size="0.02 0.02 0.319"/>
  1112. </geometry>
  1113. <material name="Gray"/>
  1114. </visual>
  1115. <visual>
  1116. <origin rpy="0 0 0" xyz="-0.14 -0.1025 0.1626"/>
  1117. <geometry>
  1118. <box size="0.02 0.02 0.319"/>
  1119. </geometry>
  1120. <material name="Gray"/>
  1121. </visual>
  1122. <collision>
  1123. <origin rpy="0 0 0" xyz="-0.14 0.1025 0.1626"/>
  1124. <geometry>
  1125. <box size="0.02 0.02 0.319"/>
  1126. </geometry>
  1127. <material name="Gray"/>
  1128. </collision>
  1129. <collision>
  1130. <origin rpy="0 0 0" xyz="-0.14 -0.1025 0.1626"/>
  1131. <geometry>
  1132. <box size="0.02 0.02 0.319"/>
  1133. </geometry>
  1134. <material name="Gray"/>
  1135. </collision>
  1136. <!-- Horizontal Profile -->
  1137. <visual>
  1138. <origin rpy="0 0 0" xyz="-0.14 0 0.3121"/>
  1139. <geometry>
  1140. <box size="0.02 0.225 0.02"/>
  1141. </geometry>
  1142. <material name="Gray"/>
  1143. </visual>
  1144. <collision>
  1145. <origin rpy="0 0 0" xyz="-0.14 0 0.3121"/>
  1146. <geometry>
  1147. <box size="0.02 0.225 0.02"/>
  1148. </geometry>
  1149. <material name="Gray"/>
  1150. </collision>
  1151. <!-- Camera360 alu mount -->
  1152. <visual>
  1153. <origin rpy="0 0 0" xyz="-0.14 0 0.3446"/>
  1154. <geometry>
  1155. <box size="0.02 0.02 0.045 "/>
  1156. </geometry>
  1157. <material name="Gray"/>
  1158. </visual>
  1159. <collision>
  1160. <origin rpy="0 0 0" xyz="-0.14 0 0.3446"/>
  1161. <geometry>
  1162. <box size="0.02 0.02 0.045 "/>
  1163. </geometry>
  1164. <material name="Gray"/>
  1165. </collision>
  1166. </link>
  1167. <gazebo reference="navigation_module_link">
  1168. <material>Gazebo/Grey</material>
  1169. </gazebo>
  1170. <joint name="realsense_d435_back_mount_joint" type="fixed">
  1171. <origin rpy="0 0 3.14159265359" xyz="-0.1601 0 0.2996"/>
  1172. <parent link="navigation_module_link"/>
  1173. <child link="realsense_d435_back_mount_link"/>
  1174. </joint>
  1175. <link name="realsense_d435_back_mount_link">
  1176. </link>
  1177. <joint name="realsense_d435_back_joint" type="fixed">
  1178. <origin rpy="0 0 0" xyz="0.0107 0.0175 0.0125"/>
  1179. <parent link="realsense_d435_back_mount_link"/>
  1180. <child link="realsense_d435_back_link"/>
  1181. </joint>
  1182. <link name="realsense_d435_back_link">
  1183. <inertial>
  1184. <mass value="0.072"/>
  1185. <origin rpy="0 0 0" xyz="0 0 0"/>
  1186. <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4"/>
  1187. </inertial>
  1188. <visual>
  1189. <origin rpy="1.57079632679 0 1.57079632679" xyz="0.0042 -0.0175 0.0"/>
  1190. <geometry>
  1191. <mesh filename="package://hector_sensors_description/meshes/intel_realsense_d435/D435.dae" scale="0.001 0.001 0.001"/>
  1192. </geometry>
  1193. </visual>
  1194. <collision>
  1195. <origin rpy="0 0 0" xyz="-0.0083 -0.0175 0.0"/>
  1196. <geometry>
  1197. <!--Dimensions taken from https://click.intel.com/intelr-realsensetm-depth-camera-d435.html-->
  1198. <box size="0.025 0.09 0.025"/>
  1199. </geometry>
  1200. </collision>
  1201. </link>
  1202. <gazebo reference="realsense_d435_back_link">
  1203. <material>Gazebo/Grey</material>
  1204. </gazebo>
  1205. <gazebo reference="realsense_d435_back_link">
  1206. <sensor name="realsense_d435_back" type="depth">
  1207. <update_rate>20</update_rate>
  1208. <camera>
  1209. <horizontal_fov>1.21125850088</horizontal_fov>
  1210. <image>
  1211. <format>B8G8R8</format>
  1212. <width>640</width>
  1213. <height>480</height>
  1214. </image>
  1215. <clip>
  1216. <near>0.3</near>
  1217. <far>9.0</far>
  1218. </clip>
  1219. </camera>
  1220. <plugin filename="libgazebo_ros_openni_kinect.so" name="realsense_d435_back_camera_controller">
  1221. <cameraName>realsense_d435_back</cameraName>
  1222. <imageTopicName>color/image_raw</imageTopicName>
  1223. <cameraInfoTopicName>color/camera_info</cameraInfoTopicName>
  1224. <depthImageTopicName>depth/image_raw</depthImageTopicName>
  1225. <depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
  1226. <pointCloudTopicName>depth/points</pointCloudTopicName>
  1227. <frameName>realsense_d435_back_color_optical_frame</frameName>
  1228. </plugin>
  1229. </sensor>
  1230. </gazebo>
  1231. <joint name="spin_lidar_joint_fixed" type="fixed">
  1232. <origin rpy="0.0 0.0 0.0" xyz="-0.1 0 0.2154"/>
  1233. <parent link="navigation_module_link"/>
  1234. <child link="spin_lidar_mount_link_fixed"/>
  1235. </joint>
  1236. <link name="spin_lidar_mount_link_fixed">
  1237. </link>
  1238. <joint name="spin_lidar_spin_joint" type="continuous">
  1239. <origin rpy="0.0 0.0 0.0" xyz="-0.1 0 0.2154"/>
  1240. <parent link="navigation_module_link"/>
  1241. <child link="spin_lidar_mount_link"/>
  1242. <axis xyz=" 0 0 1"/>
  1243. <limit effort="1000" velocity="100"/>
  1244. <joint_properties damping="500.0" friction="200.0"/>
  1245. </joint>
  1246. <link name="spin_lidar_mount_link">
  1247. <visual>
  1248. <origin rpy="0 0 3.14159265359" xyz="0 0 -0.21803"/>
  1249. <geometry>
  1250. <mesh filename="package://hector_components_description/meshes/autonomy_box/visionbox_lidar_mount_only.stl" scale="0.001 0.001 0.001"/>
  1251. </geometry>
  1252. <material name="Grey">
  1253. <color rgba="0.5 0.5 0.5 1"/>
  1254. </material>
  1255. </visual>
  1256. <inertial>
  1257. <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
  1258. <mass value="0.1"/>
  1259. <inertia ixx="9e-06" ixy="0.0" ixz="0.0" iyy="9e-06" iyz="0.0" izz="9e-06"/>
  1260. </inertial>
  1261. </link>
  1262. <joint name="spin_lidar_laser_joint" type="fixed">
  1263. <origin rpy="-2.62318 3.13398 3.14156" xyz="0.00266059 -0.00441927 0"/>
  1264. <parent link="spin_lidar_mount_link"/>
  1265. <child link="spin_lidar_laser_frame"/>
  1266. </joint>
  1267. <link name="spin_lidar_laser_frame">
  1268. <inertial>
  1269. <mass value="0.83"/>
  1270. <origin xyz="0 0 0"/>
  1271. <inertia ixx="0.00088568387" ixy="0.0" ixz="0.0" iyy="0.00088568387" iyz="0.0" izz="0.00088568387"/>
  1272. </inertial>
  1273. <visual>
  1274. <origin rpy="1.57079632679 0 3.14159265359" xyz="0 0 -0.0378"/>
  1275. <geometry>
  1276. <mesh filename="package://hector_sensors_description/meshes/vlp16/VLP16_base_1.dae" scale="0.001 0.001 0.001"/>
  1277. </geometry>
  1278. </visual>
  1279. <visual>
  1280. <origin rpy="1.57079632679 0 3.14159265359" xyz="0 0 -0.0378"/>
  1281. <geometry>
  1282. <mesh filename="package://hector_sensors_description/meshes/vlp16/VLP16_base_2.dae" scale="0.001 0.001 0.001"/>
  1283. </geometry>
  1284. </visual>
  1285. <visual>
  1286. <origin rpy="1.57079632679 0 3.14159265359" xyz="0 0 -0.0378"/>
  1287. <geometry>
  1288. <mesh filename="package://hector_sensors_description/meshes/vlp16/VLP16_scan.dae" scale="0.001 0.001 0.001"/>
  1289. </geometry>
  1290. </visual>
  1291. <collision>
  1292. <origin rpy="0 0 0" xyz="0 0 -0.00225"/>
  1293. <geometry>
  1294. <cylinder length="0.0717" radius="0.0516"/>
  1295. </geometry>
  1296. </collision>
  1297. </link>
  1298. <gazebo reference="spin_lidar_laser_frame">
  1299. <sensor name="spin_lidar_laser-VLP16" type="ray">
  1300. <pose>0 0 0 0 0 0</pose>
  1301. <visualize>false</visualize>
  1302. <update_rate>10</update_rate>
  1303. <ray>
  1304. <scan>
  1305. <horizontal>
  1306. <samples>512</samples>
  1307. <resolution>1</resolution>
  1308. <min_angle>-3.14159265359</min_angle>
  1309. <max_angle>3.14159265359</max_angle>
  1310. </horizontal>
  1311. <vertical>
  1312. <samples>8</samples>
  1313. <resolution>1</resolution>
  1314. <min_angle>-0.261799387799</min_angle>
  1315. <max_angle>0.261799387799</max_angle>
  1316. </vertical>
  1317. </scan>
  1318. <range>
  1319. <min>0.1</min>
  1320. <max>100</max>
  1321. <resolution>0.001</resolution>
  1322. </range>
  1323. <noise>
  1324. <type>gaussian</type>
  1325. <mean>0.0</mean>
  1326. <stddev>0.0</stddev>
  1327. </noise>
  1328. </ray>
  1329. <plugin filename="libgazebo_ros_velodyne_laser.so" name="gazebo_ros_laser_controller">
  1330. <topicName>/spin_lidar/vlp16</topicName>
  1331. <frameName>spin_lidar_laser_frame</frameName>
  1332. <min_range>0.1</min_range>
  1333. <max_range>100</max_range>
  1334. <gaussianNoise>0.008</gaussianNoise>
  1335. </plugin>
  1336. </sensor>
  1337. </gazebo>
  1338. <transmission name="spin_lidar_spin_joint_joint_transmission">
  1339. <type>transmission_interface/SimpleTransmission</type>
  1340. <joint name="spin_lidar_spin_joint">
  1341. <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
  1342. </joint>
  1343. <actuator name="spin_lidar_spin_joint_joint_motor">
  1344. <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
  1345. <mechanicalReduction>1</mechanicalReduction>
  1346. </actuator>
  1347. </transmission>
  1348. <gazebo reference="spin_lidar_spin_joint">
  1349. <implicitSpringDamper>1</implicitSpringDamper>
  1350. </gazebo>
  1351. <gazebo reference="spin_lidar_spin_joint">
  1352. <implicitSpringDamper>1</implicitSpringDamper>
  1353. </gazebo>
  1354. <gazebo>
  1355. <!-- ros_control plugin -->
  1356. <plugin filename="libgazebo_ros_control_select_joints.so" name="gazebo_ros_control_select_joints">
  1357. <robotNamespace>spin_lidar_control</robotNamespace>
  1358. <joints>spin_lidar_spin_joint</joints>
  1359. </plugin>
  1360. </gazebo>
  1361. <gazebo reference="spin_lidar_mount_link">
  1362. <visual>
  1363. <material>
  1364. <ambient>0.1 0.1 0.1 1</ambient>
  1365. <diffuse>0.48 0.48 0.48 1</diffuse>
  1366. <emissive>0.237 0.237 0.237 1</emissive>
  1367. <specular>0.8 0.8 0.8 1</specular>
  1368. </material>
  1369. </visual>
  1370. </gazebo>
  1371. <joint name="camera360_center_joint" type="fixed">
  1372. <origin rpy="0 0 1.57" xyz="-0.14 0 0.3871 "/>
  1373. <parent link="navigation_module_link"/>
  1374. <child link="camera360_center_link"/>
  1375. </joint>
  1376. <link name="camera360_center_link">
  1377. <!-- Sphere body -->
  1378. <visual>
  1379. <origin rpy="0 0 0" xyz="0 0 0"/>
  1380. <geometry>
  1381. <sphere radius="0.02"/>
  1382. </geometry>
  1383. <material name="Grey">
  1384. <color rgba="0.5 0.5 0.5 1"/>
  1385. </material>
  1386. </visual>
  1387. <collision>
  1388. <origin rpy="0 0 0" xyz="0 0 0"/>
  1389. <geometry>
  1390. <sphere radius="0.04"/>
  1391. </geometry>
  1392. <material name="Grey">
  1393. <color rgba="0.5 0.5 0.5 1"/>
  1394. </material>
  1395. </collision>
  1396. <!-- Cable -->
  1397. <!-- <visual>
  1398. <origin xyz="${visual_radius + cable_collision_length/2} 0 0" rpy="0 0 0"/>
  1399. <geometry>
  1400. <box size="${cable_collision_length} 0.03 0.03"/>
  1401. </geometry>
  1402. <material name="Grey">
  1403. <color rgba="0.5 0.5 0.5 1"/>
  1404. </material>
  1405. </visual>-->
  1406. <collision>
  1407. <origin rpy="0 0 0" xyz="0.036 0 0"/>
  1408. <geometry>
  1409. <box size="0.05 0.03 0.03"/>
  1410. </geometry>
  1411. <material name="Grey">
  1412. <color rgba="0.5 0.5 0.5 1"/>
  1413. </material>
  1414. </collision>
  1415. </link>
  1416. <joint name="camera360_right_joint" type="fixed">
  1417. <origin rpy="1.57079632679 0 -1.57079632679" xyz="0 -0.01925392 0"/>
  1418. <parent link="camera360_center_link"/>
  1419. <child link="camera360_right_link"/>
  1420. </joint>
  1421. <link name="camera360_right_link"/>
  1422. <joint name="camera360_right_optical_joint" type="fixed">
  1423. <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
  1424. <parent link="camera360_right_link"/>
  1425. <child link="camera360_right_optical_frame"/>
  1426. </joint>
  1427. <link name="camera360_right_optical_frame"/>
  1428. <gazebo reference="camera360_right_link">
  1429. <sensor name="camera360_right_camera_sensor" type="wideanglecamera">
  1430. <update_rate>10</update_rate>
  1431. <camera>
  1432. <!--<horizontal_fov>${hfov * M_PI/180.0}</horizontal_fov>-->
  1433. <horizontal_fov>3.14</horizontal_fov>
  1434. <image>
  1435. <format>R8G8B8</format>
  1436. <width>1504</width>
  1437. <height>1504</height>
  1438. </image>
  1439. <clip>
  1440. <near>0.01</near>
  1441. <far>100</far>
  1442. </clip>
  1443. <lens>
  1444. <!--
  1445. Crashes gazebo on some machines, so revert for now
  1446. <type>custom</type>
  1447. <custom_function>
  1448. <c1>2</c1>
  1449. <c2>2</c2>
  1450. <f>1.0</f>
  1451. <fun>sin</fun>
  1452. </custom_function>
  1453. <cutoff_angle>${fov/2}</cutoff_angle>
  1454. <env_texture_size>1024</env_texture_size>
  1455. -->
  1456. <type>stereographic</type>
  1457. <scale_to_hfov>true</scale_to_hfov>
  1458. <cutoff_angle>1.5707</cutoff_angle>
  1459. <env_texture_size>512</env_texture_size>
  1460. </lens>
  1461. </camera>
  1462. <plugin filename="libgazebo_ros_camera.so" name="camera360_right_camera_controller">
  1463. <cameraName>camera360/right</cameraName>
  1464. <imageTopicName>image_raw</imageTopicName>
  1465. <cameraInfoTopicName>not_used</cameraInfoTopicName>
  1466. <frameName>camera360_right_optical_frame</frameName>
  1467. </plugin>
  1468. </sensor>
  1469. </gazebo>
  1470. <joint name="camera360_left_optical_joint" type="fixed">
  1471. <origin rpy="3.1373499 -0.0021358 -3.1279404" xyz="0.00009742 0.00061696 -0.03850784"/>
  1472. <parent link="camera360_right_optical_frame"/>
  1473. <child link="camera360_left_optical_frame"/>
  1474. </joint>
  1475. <link name="camera360_left_optical_frame"/>
  1476. <joint name="camera360_left_joint" type="fixed">
  1477. <origin rpy="0 -1.57079632679 1.57079632679" xyz="0 0 0"/>
  1478. <parent link="camera360_left_optical_frame"/>
  1479. <child link="camera360_left_link"/>
  1480. </joint>
  1481. <link name="camera360_left_link"/>
  1482. <gazebo reference="camera360_left_link">
  1483. <sensor name="camera360_left_camera_sensor" type="wideanglecamera">
  1484. <update_rate>10</update_rate>
  1485. <camera>
  1486. <!--<horizontal_fov>${hfov * M_PI/180.0}</horizontal_fov>-->
  1487. <horizontal_fov>3.14</horizontal_fov>
  1488. <image>
  1489. <format>R8G8B8</format>
  1490. <width>1504</width>
  1491. <height>1504</height>
  1492. </image>
  1493. <clip>
  1494. <near>0.01</near>
  1495. <far>100</far>
  1496. </clip>
  1497. <lens>
  1498. <!--
  1499. Crashes gazebo on some machines, so revert for now
  1500. <type>custom</type>
  1501. <custom_function>
  1502. <c1>2</c1>
  1503. <c2>2</c2>
  1504. <f>1.0</f>
  1505. <fun>sin</fun>
  1506. </custom_function>
  1507. <cutoff_angle>${fov/2}</cutoff_angle>
  1508. <env_texture_size>1024</env_texture_size>
  1509. -->
  1510. <type>stereographic</type>
  1511. <scale_to_hfov>true</scale_to_hfov>
  1512. <cutoff_angle>1.5707</cutoff_angle>
  1513. <env_texture_size>512</env_texture_size>
  1514. </lens>
  1515. </camera>
  1516. <plugin filename="libgazebo_ros_camera.so" name="camera360_left_camera_controller">
  1517. <cameraName>camera360/left</cameraName>
  1518. <imageTopicName>image_raw</imageTopicName>
  1519. <cameraInfoTopicName>not_used</cameraInfoTopicName>
  1520. <frameName>camera360_left_optical_frame</frameName>
  1521. </plugin>
  1522. </sensor>
  1523. </gazebo>
  1524. <joint name="arm_sensor_box_joint_fixed" type="fixed">
  1525. <origin rpy="0.0 0.0 0.0" xyz="0.025 -0.058 0.0"/>
  1526. <parent link="arm_link_4"/>
  1527. <child link="arm_sensor_box_link"/>
  1528. </joint>
  1529. <link name="arm_sensor_box_link">
  1530. <origin rpy="0 0 0" xyz="0 0 0"/>
  1531. <visual>
  1532. <origin rpy="0 0 3.14159265359" xyz="0 -0.003 0"/>
  1533. <geometry>
  1534. <mesh filename="package://drz_telemax_description/meshes/arm_sensor_box_cover.stl" scale="0.001 0.001 0.001"/>
  1535. </geometry>
  1536. <material name="Black"/>
  1537. </visual>
  1538. <collision>
  1539. <origin rpy="0 0 0" xyz="0 -0.04 0.0"/>
  1540. <geometry>
  1541. <box size="0.21 0.09 0.13"/>
  1542. </geometry>
  1543. </collision>
  1544. </link>
  1545. <joint name="arm_thermal_cam_joint" type="fixed">
  1546. <origin rpy="3.14159265359 0.0 0.0" xyz="0.09 -0.023 0.0"/>
  1547. <parent link="arm_sensor_box_link"/>
  1548. <child link="arm_thermal_cam_frame"/>
  1549. </joint>
  1550. <link name="arm_thermal_cam_frame">
  1551. <inertial>
  1552. <mass value="0.03"/>
  1553. <origin xyz="0 0 0"/>
  1554. <inertia ixx="1.2e-06" ixy="0.0" ixz="0.0" iyy="1.2e-06" iyz="0.0" izz="1.2e-06"/>
  1555. </inertial>
  1556. <visual>
  1557. <origin rpy="0 1.57079632679 0" xyz="0 0.0 0.0"/>
  1558. <geometry>
  1559. <cylinder length="0.029" radius="0.016"/>
  1560. </geometry>
  1561. <material name="DarkGrey">
  1562. <color rgba="0.3 0.3 0.3 1"/>
  1563. </material>
  1564. </visual>
  1565. <visual>
  1566. <origin rpy="0 0 0" xyz="-0.02875 -0.004 0.0"/>
  1567. <geometry>
  1568. <box size="0.0285 0.0345 0.029 "/>
  1569. </geometry>
  1570. <material name="DarkGrey">
  1571. <color rgba="0.3 0.3 0.3 1"/>
  1572. </material>
  1573. </visual>
  1574. </link>
  1575. <joint name="arm_thermal_cam_optical_joint" type="fixed">
  1576. <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
  1577. <parent link="arm_thermal_cam_frame"/>
  1578. <child link="arm_thermal_cam_optical_frame"/>
  1579. </joint>
  1580. <link name="arm_thermal_cam_optical_frame"/>
  1581. <gazebo reference="arm_thermal_cam_frame">
  1582. <material>Gazebo/Grey</material>
  1583. </gazebo>
  1584. <gazebo reference="arm_thermal_cam_frame">
  1585. <sensor name="thermal_camera_sensor" type="camera">
  1586. <update_rate>9</update_rate>
  1587. <camera>
  1588. <horizontal_fov>0.872664625997</horizontal_fov>
  1589. <image>
  1590. <format>R8G8B8</format>
  1591. <width>640</width>
  1592. <height>512</height>
  1593. </image>
  1594. <clip>
  1595. <near>0.01</near>
  1596. <far>10</far>
  1597. </clip>
  1598. </camera>
  1599. <plugin filename="libgazebo_ros_thermal_camera.so" name="thermal_camera_controller">
  1600. <alwaysOn>true</alwaysOn>
  1601. <updateRate>9</updateRate>
  1602. <cameraName>arm_thermal_cam</cameraName>
  1603. <imageTopicName>image_raw</imageTopicName>
  1604. <cameraInfoTopicName>camera_info</cameraInfoTopicName>
  1605. <frameName>arm_thermal_cam_optical_frame</frameName>
  1606. </plugin>
  1607. </sensor>
  1608. </gazebo>
  1609. <joint name="arm_rgbd_cam_mount_joint" type="fixed">
  1610. <origin rpy="1.57079632679 0 0" xyz="0.0875 -0.053 0.00143"/>
  1611. <parent link="arm_sensor_box_link"/>
  1612. <child link="arm_rgbd_cam_mount_link"/>
  1613. </joint>
  1614. <link name="arm_rgbd_cam_mount_link">
  1615. </link>
  1616. <joint name="arm_rgbd_cam_joint" type="fixed">
  1617. <origin rpy="0 0 0" xyz="0.0107 0.0175 0.0125"/>
  1618. <parent link="arm_rgbd_cam_mount_link"/>
  1619. <child link="arm_rgbd_cam_link"/>
  1620. </joint>
  1621. <link name="arm_rgbd_cam_link">
  1622. <inertial>
  1623. <mass value="0.072"/>
  1624. <origin rpy="0 0 0" xyz="0 0 0"/>
  1625. <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4"/>
  1626. </inertial>
  1627. <visual>
  1628. <origin rpy="1.57079632679 0 1.57079632679" xyz="0.0042 -0.0175 0.0"/>
  1629. <geometry>
  1630. <mesh filename="package://hector_sensors_description/meshes/intel_realsense_d435/D435.dae" scale="0.001 0.001 0.001"/>
  1631. </geometry>
  1632. </visual>
  1633. <collision>
  1634. <origin rpy="0 0 0" xyz="-0.0083 -0.0175 0.0"/>
  1635. <geometry>
  1636. <!--Dimensions taken from https://click.intel.com/intelr-realsensetm-depth-camera-d435.html-->
  1637. <box size="0.025 0.09 0.025"/>
  1638. </geometry>
  1639. </collision>
  1640. </link>
  1641. <gazebo reference="arm_rgbd_cam_link">
  1642. <material>Gazebo/Grey</material>
  1643. </gazebo>
  1644. <gazebo reference="arm_rgbd_cam_link">
  1645. <sensor name="arm_rgbd_cam" type="depth">
  1646. <update_rate>20</update_rate>
  1647. <camera>
  1648. <horizontal_fov>1.21125850088</horizontal_fov>
  1649. <image>
  1650. <format>B8G8R8</format>
  1651. <width>640</width>
  1652. <height>480</height>
  1653. </image>
  1654. <clip>
  1655. <near>0.3</near>
  1656. <far>9.0</far>
  1657. </clip>
  1658. </camera>
  1659. <plugin filename="libgazebo_ros_openni_kinect.so" name="arm_rgbd_cam_camera_controller">
  1660. <cameraName>arm_rgbd_cam</cameraName>
  1661. <imageTopicName>color/image_raw</imageTopicName>
  1662. <cameraInfoTopicName>color/camera_info</cameraInfoTopicName>
  1663. <depthImageTopicName>depth/image_raw</depthImageTopicName>
  1664. <depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
  1665. <pointCloudTopicName>depth/points</pointCloudTopicName>
  1666. <frameName>arm_rgbd_cam_color_optical_frame</frameName>
  1667. </plugin>
  1668. </sensor>
  1669. </gazebo>
  1670. <joint name="arm_wide_angle_cam_joint" type="fixed">
  1671. <origin rpy="1.57079632679 0 0" xyz="0.095 -0.02133 -0.03768"/>
  1672. <parent link="arm_sensor_box_link"/>
  1673. <child link="arm_wide_angle_cam_link"/>
  1674. </joint>
  1675. <link name="arm_wide_angle_cam_link">
  1676. <!-- <inertial>
  1677. <mass value="0.001" />
  1678. <origin xyz="0 0 0" rpy="0 0 0" />
  1679. <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
  1680. </inertial>
  1681. <visual>
  1682. <origin xyz="0 0 0" rpy="0 0 0" />
  1683. <geometry>
  1684. <box size="0.01 0.01 0.01" />
  1685. </geometry>
  1686. <material name="Blue">
  1687. <color rgba="0.0 0.0 0.8 1"/>
  1688. </material>
  1689. </visual>
  1690. <collision>
  1691. <origin xyz="0 0 0" rpy="0 0 0" />
  1692. <geometry>
  1693. <box size="0.01 0.01 0.01" />
  1694. </geometry>
  1695. </collision>-->
  1696. </link>
  1697. <joint name="arm_wide_angle_cam_optical_joint" type="fixed">
  1698. <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
  1699. <parent link="arm_wide_angle_cam_link"/>
  1700. <child link="arm_wide_angle_cam_optical_frame"/>
  1701. </joint>
  1702. <link name="arm_wide_angle_cam_optical_frame"/>
  1703. <gazebo reference="arm_wide_angle_cam_link">
  1704. <sensor name="arm_wide_angle_cam_camera_sensor" type="camera">
  1705. <update_rate>5</update_rate>
  1706. <camera>
  1707. <horizontal_fov>2.26892802759</horizontal_fov>
  1708. <image>
  1709. <format>R8G8B8</format>
  1710. <width>1920</width>
  1711. <height>1080</height>
  1712. </image>
  1713. <clip>
  1714. <near>0.01</near>
  1715. <far>100</far>
  1716. </clip>
  1717. </camera>
  1718. <plugin filename="libgazebo_ros_camera.so" name="arm_wide_angle_cam_camera_controller">
  1719. <cameraName>arm_wide_angle_cam</cameraName>
  1720. <imageTopicName>/arm_wide_angle_cam/image_raw</imageTopicName>
  1721. <cameraInfoTopicName>/arm_wide_angle_cam/camera_info</cameraInfoTopicName>
  1722. <frameName>arm_wide_angle_cam_optical_frame</frameName>
  1723. </plugin>
  1724. </sensor>
  1725. </gazebo>
  1726. <joint name="arm_tele_cam_joint" type="fixed">
  1727. <origin rpy="1.57079632679 0 0" xyz="0.09 -0.02133 0.03768"/>
  1728. <parent link="arm_sensor_box_link"/>
  1729. <child link="arm_tele_cam_link"/>
  1730. </joint>
  1731. <link name="arm_tele_cam_link">
  1732. <!-- <inertial>
  1733. <mass value="0.001" />
  1734. <origin xyz="0 0 0" rpy="0 0 0" />
  1735. <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
  1736. </inertial>
  1737. <visual>
  1738. <origin xyz="0 0 0" rpy="0 0 0" />
  1739. <geometry>
  1740. <box size="0.01 0.01 0.01" />
  1741. </geometry>
  1742. <material name="Blue">
  1743. <color rgba="0.0 0.0 0.8 1"/>
  1744. </material>
  1745. </visual>
  1746. <collision>
  1747. <origin xyz="0 0 0" rpy="0 0 0" />
  1748. <geometry>
  1749. <box size="0.01 0.01 0.01" />
  1750. </geometry>
  1751. </collision>-->
  1752. </link>
  1753. <joint name="arm_tele_cam_optical_joint" type="fixed">
  1754. <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
  1755. <parent link="arm_tele_cam_link"/>
  1756. <child link="arm_tele_cam_optical_frame"/>
  1757. </joint>
  1758. <link name="arm_tele_cam_optical_frame"/>
  1759. <gazebo reference="arm_tele_cam_link">
  1760. <sensor name="arm_tele_cam_camera_sensor" type="camera">
  1761. <update_rate>1</update_rate>
  1762. <camera>
  1763. <horizontal_fov>0.698131700798</horizontal_fov>
  1764. <image>
  1765. <format>R8G8B8</format>
  1766. <width>1920</width>
  1767. <height>1080</height>
  1768. </image>
  1769. <clip>
  1770. <near>0.01</near>
  1771. <far>100</far>
  1772. </clip>
  1773. </camera>
  1774. <plugin filename="libgazebo_ros_camera.so" name="arm_tele_cam_camera_controller">
  1775. <cameraName>arm_tele_cam</cameraName>
  1776. <imageTopicName>/arm_tele_cam/image_raw</imageTopicName>
  1777. <cameraInfoTopicName>/arm_tele_cam/camera_info</cameraInfoTopicName>
  1778. <frameName>arm_tele_cam_optical_frame</frameName>
  1779. </plugin>
  1780. </sensor>
  1781. </gazebo>
  1782. </robot>