gazebo.urdf.xacro 7.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242
  1. <?xml version="1.0"?>
  2. <robot xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
  3. xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
  4. xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
  5. xmlns:xacro="http://ros.org/wiki/xacro" name="turtlebot_gazebo">
  6. <!-- ASUS Xtion PRO camera for simulation -->
  7. <!-- gazebo_ros_wge100 plugin is in kt2_gazebo_plugins package -->
  8. <xacro:macro name="turtlebot_sim_asus_xtion">
  9. <gazebo reference="camera_link" >
  10. <sensor:camera name="camera" >
  11. <imageSize>640 480</imageSize>
  12. <imageFormat>R8G8B8</imageFormat>
  13. <hfov>62.8</hfov>
  14. <nearClip>0.1</nearClip>
  15. <farClip>10</farClip>
  16. <updateRate>2.0</updateRate>
  17. <controller:gazebo_ros_wge100 name="kinect_camera_controller" plugin="libgazebo_ros_wge100.so">
  18. <alwaysOn>true</alwaysOn>
  19. <updateRate>5000.0</updateRate>
  20. <cameraName>camera/rgb</cameraName>
  21. <frameName>camera_rgb_optical_frame</frameName>
  22. <hackBaseline>0.0</hackBaseline>
  23. <CxPrime>320.5</CxPrime>
  24. <Cx>320.5</Cx>
  25. <Cy>240.5</Cy>
  26. <baseline>0.09</baseline>
  27. <!-- image_width / (2*tan(hfov_radian /2)) -->
  28. <!-- 320 for wide and 772.55 for narrow stereo camera -->
  29. <focal_length>525</focal_length>
  30. <cameraNamespace>camera/rgb</cameraNamespace>
  31. <depthData>true</depthData>
  32. <interface:camera name="camera_iface" />
  33. </controller:gazebo_ros_wge100>
  34. </sensor:camera>
  35. </gazebo>
  36. </xacro:macro>
  37. <xacro:macro name="turtlebot_sim_kinect">
  38. <gazebo reference="camera_link">
  39. <sensor:camera name="camera">
  40. <imageFormat>R8G8B8</imageFormat>
  41. <imageSize>640 480</imageSize>
  42. <hfov>60</hfov>
  43. <nearClip>0.05</nearClip>
  44. <farClip>3</farClip>
  45. <updateRate>20</updateRate>
  46. <baseline>0.1</baseline>
  47. <controller:gazebo_ros_openni_kinect name="kinect_camera_controller" plugin="libgazebo_ros_openni_kinect.so">
  48. <alwaysOn>true</alwaysOn>
  49. <updateRate>20</updateRate>
  50. <imageTopicName>/camera/image_raw</imageTopicName>
  51. <pointCloudTopicName>/camera/depth/points</pointCloudTopicName>
  52. <cameraInfoTopicName>/camera/camera_info</cameraInfoTopicName>
  53. <frameName>camera_depth_optical_frame</frameName>
  54. <distortion_k1>0.0</distortion_k1>
  55. <distortion_k2>0.0</distortion_k2>
  56. <distortion_k3>0.0</distortion_k3>
  57. <distortion_t1>0.0</distortion_t1>
  58. <distortion_t2>0.0</distortion_t2>
  59. </controller:gazebo_ros_openni_kinect>
  60. </sensor:camera>
  61. </gazebo>
  62. </xacro:macro>
  63. <xacro:macro name="turtlebot_sim_imu">
  64. <gazebo>
  65. <controller:gazebo_ros_imu name="imu_controller" plugin="libgazebo_ros_imu.so">
  66. <alwaysOn>true</alwaysOn>
  67. <updateRate>30</updateRate>
  68. <bodyName>gyro_link</bodyName>
  69. <topicName>imu/data</topicName>
  70. <gaussianNoise>${0.0017*0.0017}</gaussianNoise>
  71. <xyzOffsets>0 0 0</xyzOffsets>
  72. <rpyOffsets>0 0 0</rpyOffsets>
  73. <interface:position name="imu_position"/>
  74. </controller:gazebo_ros_imu>
  75. </gazebo>
  76. </xacro:macro>
  77. <xacro:macro name="turtlebot_sim_laser">
  78. <gazebo reference="laser">
  79. <sensor:ray name="laser">
  80. <rayCount>180</rayCount>
  81. <rangeCount>180</rangeCount>
  82. <laserCount>1</laserCount>
  83. <origin>0.0 0.0 0.0</origin>
  84. <displayRays>false</displayRays>
  85. <minAngle>-130</minAngle>
  86. <maxAngle>130</maxAngle>
  87. <minRange>0.08</minRange>
  88. <maxRange>10.0</maxRange>
  89. <resRange>0.01</resRange>
  90. <updateRate>20</updateRate>
  91. <controller:gazebo_ros_laser name="gazebo_ros_laser_controller" plugin="libgazebo_ros_laser.so">
  92. <gaussianNoise>0.005</gaussianNoise>
  93. <alwaysOn>true</alwaysOn>
  94. <updateRate>20</updateRate>
  95. <topicName>scan</topicName>
  96. <frameName>laser</frameName>
  97. <interface:laser name="gazebo_ros_laser_iface" />
  98. </controller:gazebo_ros_laser>
  99. </sensor:ray>
  100. </gazebo>
  101. </xacro:macro>
  102. <xacro:macro name="turtlebot_sim_create">
  103. <gazebo>
  104. <controller:gazebo_ros_create name="create_controller" plugin="libgazebo_ros_create.so">
  105. <alwaysOn>true</alwaysOn>
  106. <node_namespace>turtlebot_node</node_namespace>
  107. <left_wheel_joint>left_wheel_joint</left_wheel_joint>
  108. <right_wheel_joint>right_wheel_joint</right_wheel_joint>
  109. <front_castor_joint>front_castor_joint</front_castor_joint>
  110. <rear_castor_joint>rear_castor_joint</rear_castor_joint>
  111. <wheel_separation>.260</wheel_separation>
  112. <wheel_diameter>0.066</wheel_diameter>
  113. <base_geom>base_link_geom_base_link</base_geom>
  114. <updateRate>40</updateRate>
  115. <torque>1.0</torque>
  116. </controller:gazebo_ros_create>
  117. </gazebo>
  118. </xacro:macro>
  119. <xacro:macro name="turtlebot_sim_wall_sensors">
  120. <gazebo reference="wall_sensor_link">
  121. <sensor:ray name="wall_sensor">
  122. <alwaysActive>true</alwaysActive>
  123. <rayCount>1</rayCount>
  124. <rangeCount>1</rangeCount>
  125. <resRange>0.1</resRange>
  126. <minAngle>0</minAngle>
  127. <maxAngle>0</maxAngle>
  128. <minRange>0.0160</minRange>
  129. <maxRange>0.04</maxRange>
  130. <displayRays>false</displayRays>
  131. </sensor:ray>
  132. </gazebo>
  133. <gazebo reference="left_cliff_sensor_link">
  134. <sensor:ray name="left_cliff_sensor">
  135. <alwaysActive>true</alwaysActive>
  136. <rayCount>1</rayCount>
  137. <rangeCount>1</rangeCount>
  138. <resRange>0.1</resRange>
  139. <minAngle>0</minAngle>
  140. <maxAngle>0</maxAngle>
  141. <minRange>0.01</minRange>
  142. <maxRange>0.04</maxRange>
  143. <displayRays>false</displayRays>
  144. </sensor:ray>
  145. </gazebo>
  146. <gazebo reference="right_cliff_sensor_link">
  147. <sensor:ray name="right_cliff_sensor">
  148. <alwaysActive>true</alwaysActive>
  149. <rayCount>1</rayCount>
  150. <rangeCount>1</rangeCount>
  151. <resRange>0.1</resRange>
  152. <minAngle>0</minAngle>
  153. <maxAngle>0</maxAngle>
  154. <minRange>0.01</minRange>
  155. <maxRange>0.04</maxRange>
  156. <displayRays>false</displayRays>
  157. </sensor:ray>
  158. </gazebo>
  159. <gazebo reference="leftfront_cliff_sensor_link">
  160. <sensor:ray name="leftfront_cliff_sensor">
  161. <alwaysActive>true</alwaysActive>
  162. <rayCount>1</rayCount>
  163. <rangeCount>1</rangeCount>
  164. <resRange>0.1</resRange>
  165. <minAngle>0</minAngle>
  166. <maxAngle>0</maxAngle>
  167. <minRange>0.01</minRange>
  168. <maxRange>0.04</maxRange>
  169. <displayRays>false</displayRays>
  170. </sensor:ray>
  171. </gazebo>
  172. <gazebo reference="rightfront_cliff_sensor_link">
  173. <sensor:ray name="rightfront_cliff_sensor">
  174. <alwaysActive>true</alwaysActive>
  175. <rayCount>1</rayCount>
  176. <rangeCount>1</rangeCount>
  177. <resRange>0.1</resRange>
  178. <minAngle>0</minAngle>
  179. <maxAngle>0</maxAngle>
  180. <minRange>0.01</minRange>
  181. <maxRange>0.04</maxRange>
  182. <displayRays>fan</displayRays>
  183. </sensor:ray>
  184. </gazebo>
  185. <gazebo reference="left_wheel_link">
  186. <mu1 value="10"/>
  187. <mu2 value="10"/>
  188. <kp value="100000000.0"/>
  189. <kd value="10000.0"/>
  190. <fdir value="1 0 0"/>
  191. </gazebo>
  192. <gazebo reference="right_wheel_link">
  193. <mu1 value="10"/>
  194. <mu2 value="10"/>
  195. <kp value="100000000.0"/>
  196. <kd value="10000.0"/>
  197. <fdir value="1 0 0"/>
  198. </gazebo>
  199. <gazebo reference="rear_wheel_link">
  200. <mu1 value="0"/>
  201. <mu2 value="0"/>
  202. <kp value="100000000.0"/>
  203. <kd value="10000.0"/>
  204. </gazebo>
  205. <gazebo reference="front_wheel_link">
  206. <mu1 value="0"/>
  207. <mu2 value="0"/>
  208. <kp value="100000000.0"/>
  209. <kd value="10000.0"/>
  210. </gazebo>
  211. </xacro:macro>
  212. </robot>