rosbot_xl.urdf 7.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201
  1. <?xml version="1.0" ?>
  2. <!-- =================================================================================== -->
  3. <!-- | This document was autogenerated by xacro from /home/michal/ros2_ws/src/rosbot_xl_description/urdf/rosbot_xl.urdf.xacro | -->
  4. <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
  5. <!-- =================================================================================== -->
  6. <robot name="rosbot_xl">
  7. <link name="base_link"/>
  8. <joint name="base_to_body_joint" type="fixed">
  9. <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.048"/>
  10. <parent link="base_link"/>
  11. <child link="body_link"/>
  12. </joint>
  13. <link name="body_link">
  14. <visual>
  15. <geometry>
  16. <mesh filename="meshes/body.fbx" scale="1 1 1"/>
  17. </geometry>
  18. <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
  19. </visual>
  20. <collision>
  21. <geometry>
  22. <mesh filename="meshes/body_colision.stl" scale="1 1 1"/>
  23. </geometry>
  24. <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
  25. </collision>
  26. <inertial>
  27. <mass value="3.5"/>
  28. <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0358"/>
  29. <inertia ixx="0.01393" ixy="-0.000020968097" ixz="0.000010399694" iyy="0.01081" iyz="0.000059372953" izz="0.02048"/>
  30. </inertial>
  31. </link>
  32. <joint name="body_to_cover_joint" type="fixed">
  33. <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.08345"/>
  34. <parent link="body_link"/>
  35. <child link="cover_link"/>
  36. </joint>
  37. <link name="cover_link"/>
  38. <joint name="body_to_imu_joint" type="fixed">
  39. <origin rpy="3.14159 0.0 0.0" xyz="-0.1369 -0.0419 0.0370"/>
  40. <parent link="body_link"/>
  41. <child link="imu_link"/>
  42. </joint>
  43. <link name="imu_link"/>
  44. <joint name="fl_wheel_joint" type="continuous">
  45. <parent link="body_link"/>
  46. <child link="fl_wheel_link"/>
  47. <origin rpy="0.0 0.0 0.0" xyz="0.085 0.124 0.0"/>
  48. <axis xyz="0.0 1.0 0.0"/>
  49. <limit effort="1.27" velocity="21.0"/>
  50. <dynamics damping="0.001" friction="0.001"/>
  51. </joint>
  52. <link name="fl_wheel_link">
  53. <visual>
  54. <geometry>
  55. <mesh filename="meshes/wheel_b.dae" scale="1 1 1"/>
  56. </geometry>
  57. <origin rpy="0.0 0.0 3.141592653589793" xyz="0.0 0.0 0.0"/>
  58. </visual>
  59. <collision>
  60. <geometry>
  61. <cylinder length="0.036" radius="0.048"/>
  62. </geometry>
  63. <origin rpy="1.5707963267948966 0.0 0.0" xyz="0.0 0.0 0.0"/>
  64. </collision>
  65. <inertial>
  66. <mass value="0.051"/>
  67. <inertia ixx="5.0587413e-05" ixy="0.0" ixz="0.0" iyy="8.5933192e-05" iyz="0.0" izz="5.0587829e-05"/>
  68. </inertial>
  69. </link>
  70. <joint name="fr_wheel_joint" type="continuous">
  71. <parent link="body_link"/>
  72. <child link="fr_wheel_link"/>
  73. <origin rpy="0.0 0.0 0.0" xyz="0.085 -0.124 0.0"/>
  74. <axis xyz="0.0 1.0 0.0"/>
  75. <limit effort="1.27" velocity="21.0"/>
  76. <dynamics damping="0.001" friction="0.001"/>
  77. </joint>
  78. <link name="fr_wheel_link">
  79. <visual>
  80. <geometry>
  81. <mesh filename="meshes/wheel_a.dae" scale="1 1 1"/>
  82. </geometry>
  83. <origin rpy="0.0 0.0 3.141592653589793" xyz="0.0 0.0 0.0"/>
  84. </visual>
  85. <collision>
  86. <geometry>
  87. <cylinder length="0.036" radius="0.048"/>
  88. </geometry>
  89. <origin rpy="1.5707963267948966 0.0 0.0" xyz="0.0 0.0 0.0"/>
  90. </collision>
  91. <inertial>
  92. <mass value="0.051"/>
  93. <inertia ixx="5.0587413e-05" ixy="0.0" ixz="0.0" iyy="8.5933192e-05" iyz="0.0" izz="5.0587829e-05"/>
  94. </inertial>
  95. </link>
  96. <joint name="rl_wheel_joint" type="continuous">
  97. <parent link="body_link"/>
  98. <child link="rl_wheel_link"/>
  99. <origin rpy="0.0 0.0 0.0" xyz="-0.085 0.124 0.0"/>
  100. <axis xyz="0.0 1.0 0.0"/>
  101. <limit effort="1.27" velocity="21.0"/>
  102. <dynamics damping="0.001" friction="0.001"/>
  103. </joint>
  104. <link name="rl_wheel_link">
  105. <visual>
  106. <geometry>
  107. <mesh filename="meshes/wheel_a.dae" scale="1 1 1"/>
  108. </geometry>
  109. <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
  110. </visual>
  111. <collision>
  112. <geometry>
  113. <cylinder length="0.036" radius="0.048"/>
  114. </geometry>
  115. <origin rpy="1.5707963267948966 0.0 0.0" xyz="0.0 0.0 0.0"/>
  116. </collision>
  117. <inertial>
  118. <mass value="0.051"/>
  119. <inertia ixx="5.0587413e-05" ixy="0.0" ixz="0.0" iyy="8.5933192e-05" iyz="0.0" izz="5.0587829e-05"/>
  120. </inertial>
  121. </link>
  122. <joint name="rr_wheel_joint" type="continuous">
  123. <parent link="body_link"/>
  124. <child link="rr_wheel_link"/>
  125. <origin rpy="0.0 0.0 0.0" xyz="-0.085 -0.124 0.0"/>
  126. <axis xyz="0.0 1.0 0.0"/>
  127. <limit effort="1.27" velocity="21.0"/>
  128. <dynamics damping="0.001" friction="0.001"/>
  129. </joint>
  130. <link name="rr_wheel_link">
  131. <visual>
  132. <geometry>
  133. <mesh filename="meshes/wheel_b.dae" scale="1 1 1"/>
  134. </geometry>
  135. <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
  136. </visual>
  137. <collision>
  138. <geometry>
  139. <cylinder length="0.036" radius="0.048"/>
  140. </geometry>
  141. <origin rpy="1.5707963267948966 0.0 0.0" xyz="0.0 0.0 0.0"/>
  142. </collision>
  143. <inertial>
  144. <mass value="0.051"/>
  145. <inertia ixx="5.0587413e-05" ixy="0.0" ixz="0.0" iyy="8.5933192e-05" iyz="0.0" izz="5.0587829e-05"/>
  146. </inertial>
  147. </link>
  148. <ros2_control name="imu" type="sensor">
  149. <hardware>
  150. <plugin>rosbot_hardware_interfaces/RosbotImuSensor</plugin>
  151. <param name="connection_timeout_ms">120000</param>
  152. <param name="connection_check_period_ms">500</param>
  153. </hardware>
  154. <sensor name="imu">
  155. <state_interface name="orientation.x"/>
  156. <state_interface name="orientation.y"/>
  157. <state_interface name="orientation.z"/>
  158. <state_interface name="orientation.w"/>
  159. <state_interface name="angular_velocity.x"/>
  160. <state_interface name="angular_velocity.y"/>
  161. <state_interface name="angular_velocity.z"/>
  162. <state_interface name="linear_acceleration.x"/>
  163. <state_interface name="linear_acceleration.y"/>
  164. <state_interface name="linear_acceleration.z"/>
  165. </sensor>
  166. </ros2_control>
  167. <ros2_control name="wheels" type="system">
  168. <hardware>
  169. <plugin>rosbot_hardware_interfaces/RosbotSystem</plugin>
  170. <param name="connection_timeout_ms">120000</param>
  171. <param name="connection_check_period_ms">500</param>
  172. <!-- order of velocity commands to be published in motors_cmd Float32MultiArray msg -->
  173. <param name="velocity_command_joint_order">
  174. rr_wheel_joint,
  175. rl_wheel_joint,
  176. fr_wheel_joint,
  177. fl_wheel_joint
  178. </param>
  179. </hardware>
  180. <joint name="fl_wheel_joint">
  181. <command_interface name="velocity"/>
  182. <state_interface name="position"/>
  183. <state_interface name="velocity"/>
  184. </joint>
  185. <joint name="fr_wheel_joint">
  186. <command_interface name="velocity"/>
  187. <state_interface name="position"/>
  188. <state_interface name="velocity"/>
  189. </joint>
  190. <joint name="rl_wheel_joint">
  191. <command_interface name="velocity"/>
  192. <state_interface name="position"/>
  193. <state_interface name="velocity"/>
  194. </joint>
  195. <joint name="rr_wheel_joint">
  196. <command_interface name="velocity"/>
  197. <state_interface name="position"/>
  198. <state_interface name="velocity"/>
  199. </joint>
  200. </ros2_control>
  201. </robot>