robot_body.urdf.xacro 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192
  1. <?xml version="1.0"?>
  2. <robot name="mecanum_robot" xmlns:xacro="http://ros.org/wiki/xacro">
  3. <property name="M_PI" value="3.14159"/>
  4. <!-- Macro for mecanum_robot body. Including Gazebo extensions, but does not include lidar -->
  5. <include filename="$(find gazebo_robot)/urdf/gazebo.urdf.xacro"/>
  6. <property name="base_x" value="0.33" />
  7. <property name="base_y" value="0.33" />
  8. <xacro:macro name="mecanum_robot_body">
  9. <link name="base_link">
  10. <inertial>
  11. <origin xyz="0 0 0.055"/>
  12. <mass value="100.0" />
  13. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  14. </inertial>
  15. <visual>
  16. <geometry>
  17. <box size="0.25 .16 .05"/>
  18. </geometry>
  19. <origin rpy="0 0 0" xyz="0 0 0.055"/>
  20. <material name="blue">
  21. <color rgba="0 0 .8 1"/>
  22. </material>
  23. </visual>
  24. <collision>
  25. <origin rpy="0 0 0" xyz="0 0 0.055"/>
  26. <geometry>
  27. <box size="0.25 .16 .05" />
  28. </geometry>
  29. </collision>
  30. </link>
  31. <link name="left_front_wheel">
  32. <inertial>
  33. <origin xyz="0.08 0.08 0.025"/>
  34. <mass value="1" />
  35. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  36. </inertial>
  37. <visual>
  38. <geometry>
  39. <cylinder length=".02" radius="0.025"/>
  40. </geometry>
  41. <material name="black">
  42. <color rgba="0 0 0 1"/>
  43. </material>
  44. </visual>
  45. <collision>
  46. <origin rpy="0 1.57075 1.57075" xyz="0.08 0.08 0.025"/>
  47. <geometry>
  48. <cylinder length=".02" radius="0.025"/>
  49. </geometry>
  50. </collision>
  51. </link>
  52. <joint name="left_front_wheel_joint" type="continuous">
  53. <axis xyz="0 0 1"/>
  54. <parent link="base_link"/>
  55. <child link="left_front_wheel"/>
  56. <origin rpy="0 1.57075 1.57075" xyz="0.08 0.08 0.025"/>
  57. <limit effort="100" velocity="100"/>
  58. <joint_properties damping="0.0" friction="0.0"/>
  59. </joint>
  60. <link name="right_front_wheel">
  61. <inertial>
  62. <origin xyz="0.08 -0.08 0.025"/>
  63. <mass value="1" />
  64. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  65. </inertial>
  66. <visual>
  67. <geometry>
  68. <cylinder length=".02" radius="0.025"/>
  69. </geometry>
  70. <material name="black">
  71. <color rgba="0 0 0 1"/>
  72. </material>
  73. </visual>
  74. <collision>
  75. <origin rpy="0 1.57075 1.57075" xyz="0.08 -0.08 0.025"/>
  76. <geometry>
  77. <cylinder length=".02" radius="0.025"/>
  78. </geometry>
  79. </collision>
  80. </link>
  81. <joint name="right_front_wheel_joint" type="continuous">
  82. <axis xyz="0 0 1"/>
  83. <parent link="base_link"/>
  84. <child link="right_front_wheel"/>
  85. <origin rpy="0 1.57075 1.57075" xyz="0.08 -0.08 0.025"/>
  86. <limit effort="100" velocity="100"/>
  87. <joint_properties damping="0.0" friction="0.0"/>
  88. </joint>
  89. <link name="left_back_wheel">
  90. <inertial>
  91. <origin xyz="-0.08 0.08 0.025"/>
  92. <mass value="1" />
  93. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  94. </inertial>
  95. <visual>
  96. <geometry>
  97. <cylinder length=".02" radius="0.025"/>
  98. </geometry>
  99. <material name="black">
  100. <color rgba="0 0 0 1"/>
  101. </material>
  102. </visual>
  103. <collision>
  104. <origin rpy="0 1.57075 1.57075" xyz="-0.08 0.08 0.025"/>
  105. <geometry>
  106. <cylinder length=".02" radius="0.025"/>
  107. </geometry>
  108. </collision>
  109. </link>
  110. <joint name="left_back_wheel_joint" type="continuous">
  111. <axis xyz="0 0 1"/>
  112. <parent link="base_link"/>
  113. <child link="left_back_wheel"/>
  114. <origin rpy="0 1.57075 1.57075" xyz="-0.08 0.08 0.025"/>
  115. <limit effort="100" velocity="100"/>
  116. <joint_properties damping="0.0" friction="0.0"/>
  117. </joint>
  118. <link name="right_back_wheel">
  119. <inertial>
  120. <origin xyz="-0.08 -0.08 0.025"/>
  121. <mass value="1" />
  122. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  123. </inertial>
  124. <visual>
  125. <geometry>
  126. <cylinder length=".02" radius="0.025"/>
  127. </geometry>
  128. <material name="black">
  129. <color rgba="0 0 0 1"/>
  130. </material>
  131. </visual>
  132. <collision>
  133. <origin rpy="0 1.57075 1.57075" xyz="-0.08 -0.08 0.025"/>
  134. <geometry>
  135. <cylinder length=".02" radius="0.025"/>
  136. </geometry>
  137. </collision>
  138. </link>
  139. <joint name="right_back_wheel_joint" type="continuous">
  140. <axis xyz="0 0 1"/>
  141. <parent link="base_link"/>
  142. <child link="right_back_wheel"/>
  143. <origin rpy="0 1.57075 1.57075" xyz="-0.08 -0.08 0.025"/>
  144. <limit effort="100" velocity="100"/>
  145. <joint_properties damping="0.0" friction="0.0"/>
  146. </joint>
  147. <link name="head">
  148. <inertial>
  149. <origin xyz="0.08 0 0.08"/>
  150. <mass value="1" />
  151. <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
  152. </inertial>
  153. <visual>
  154. <geometry>
  155. <box size=".02 .03 .03"/>
  156. </geometry>
  157. <material name="white">
  158. <color rgba="1 1 1 1"/>
  159. </material>
  160. </visual>
  161. <collision>
  162. <origin xyz="0.08 0 0.08"/>
  163. <geometry>
  164. <cylinder length=".02" radius="0.025"/>
  165. </geometry>
  166. </collision>
  167. </link>
  168. <joint name="tobox" type="fixed">
  169. <parent link="base_link"/>
  170. <child link="head"/>
  171. <origin xyz="0.08 0 0.08"/>
  172. </joint>
  173. </xacro:macro>
  174. </robot>