|
| 1 | +<?xml version="1.0" ?> |
| 2 | +<robot xmlns:xacro="http://ros.org/wiki/xacro"> |
| 3 | + <xacro:include filename="$(find custom_robots)/models/turtlebo3/turtlebo3_gz.urdf.xacro"/> |
| 4 | + |
| 5 | + <xacro:macro name="turtlebot3"> |
| 6 | + |
| 7 | + <link name="base_footprint"></link> |
| 8 | + |
| 9 | + <link name="base_link"> |
| 10 | + <inertial> |
| 11 | + <mass value="1.373"/> |
| 12 | + <inertia ixx="4.2111447e-02" ixy="0" ixz="0" iyy="4.2111447e-02" iyz="0" izz="7.5254874e-02"/> |
| 13 | + </inertial> |
| 14 | + <collision> |
| 15 | + <origin rpy="0 0 0" xyz="-0.064 0 0.048"/> |
| 16 | + <geometry> |
| 17 | + <box size="0.265 0.265 0.089"/> |
| 18 | + </geometry> |
| 19 | + </collision> |
| 20 | + <visual > |
| 21 | + <origin rpy="0 0 0" xyz="-0.064 0 0"/> |
| 22 | + <geometry> |
| 23 | + <mesh filename="$(find custom_robots)/model/urtlebot3/meshes/waffle_base.dae" scale="0.001 0.001 0.001"/> |
| 24 | + </geometry> |
| 25 | + <gazebo> |
| 26 | + <material> |
| 27 | + <ambient>1 1 1 1</ambient> |
| 28 | + <diffuse>1 1 1 1</diffuse> |
| 29 | + <specular>0.2 0.2 0.2 1</specular> |
| 30 | + <emissive>0 0 0 1</emissive> |
| 31 | + <script> |
| 32 | + <name>Gazebo/Grey</name> |
| 33 | + </script> |
| 34 | + </material> |
| 35 | + </gazebo> |
| 36 | + </visual> |
| 37 | + </link> |
| 38 | + |
| 39 | + <link name="wheel_left_link"> |
| 40 | + <inertial> |
| 41 | + <origin rpy="-1.57 0 0" xyz="0.0 0.144 0.023"/> |
| 42 | + <mass value="0.1"/> |
| 43 | + <inertia ixx="1.1175580e-05" ixy="0" ixz="0" iyy="1.1175580e-05" iyz="0" izz="2.0712558e-05"/> |
| 44 | + </inertial> |
| 45 | + <collision> |
| 46 | + <origin rpy="-1.57 0 0" xyz="0.0 0.144 0.023"/> |
| 47 | + <geometry> |
| 48 | + <cylinder radius="0.033" length="0.018"/> |
| 49 | + </geometry> |
| 50 | + <gazebo> |
| 51 | + <surface> |
| 52 | + <!-- This friction pamareter don't contain reliable data!! --> |
| 53 | + <friction> |
| 54 | + <ode> |
| 55 | + <mu>100000.0</mu> |
| 56 | + <mu2>100000.0</mu2> |
| 57 | + <fdir1>0 0 0</fdir1> |
| 58 | + <slip1>0.0</slip1> |
| 59 | + <slip2>0.0</slip2> |
| 60 | + </ode> |
| 61 | + </friction> |
| 62 | + <contact> |
| 63 | + <ode> |
| 64 | + <soft_cfm>0</soft_cfm> |
| 65 | + <soft_erp>0.2</soft_erp> |
| 66 | + <kp>1e+5</kp> |
| 67 | + <kd>1</kd> |
| 68 | + <max_vel>0.01</max_vel> |
| 69 | + <min_depth>0.001</min_depth> |
| 70 | + </ode> |
| 71 | + </contact> |
| 72 | + </surface> |
| 73 | + </gazebo> |
| 74 | + </collision> |
| 75 | + <visual > |
| 76 | + <origin rpy="0 0 0" xyz="0.0 0.144 0.023"/> |
| 77 | + <geometry> |
| 78 | + <mesh filename="$(find custom_robots)/model/urtlebot3/meshes/tire.dae" scale="0.001 0.001 0.001"/> |
| 79 | + </geometry> |
| 80 | + <gazebo> |
| 81 | + <material> |
| 82 | + <ambient>1 1 1 1</ambient> |
| 83 | + <diffuse>1 1 1 1</diffuse> |
| 84 | + <specular>0.2 0.2 0.2 1</specular> |
| 85 | + <emissive>0 0 0 1</emissive> |
| 86 | + </material> |
| 87 | + </gazebo> |
| 88 | + </visual> |
| 89 | + </link> |
| 90 | + |
| 91 | + <link name="wheel_right_link"> |
| 92 | + <inertial> |
| 93 | + <origin rpy="-1.57 0 0" xyz="0.0 -0.144 0.023"/> |
| 94 | + <mass value="0.1"/> |
| 95 | + <inertia ixx="1.1175580e-05" ixy="0" ixz="0" iyy="1.1175580e-05" iyz="0" izz="2.0712558e-05"/> |
| 96 | + </inertial> |
| 97 | + <collision> |
| 98 | + <origin rpy="-1.57 0 0" xyz="0.0 -0.144 0.023"/> |
| 99 | + <geometry> |
| 100 | + <cylinder radius="0.033" length="0.018"/> |
| 101 | + </geometry> |
| 102 | + <gazebo> |
| 103 | + <surface> |
| 104 | + <!-- This friction pamareter don't contain reliable data!! --> |
| 105 | + <friction> |
| 106 | + <ode> |
| 107 | + <mu>100000.0</mu> |
| 108 | + <mu2>100000.0</mu2> |
| 109 | + <fdir1>0 0 0</fdir1> |
| 110 | + <slip1>0.0</slip1> |
| 111 | + <slip2>0.0</slip2> |
| 112 | + </ode> |
| 113 | + </friction> |
| 114 | + <contact> |
| 115 | + <ode> |
| 116 | + <soft_cfm>0</soft_cfm> |
| 117 | + <soft_erp>0.2</soft_erp> |
| 118 | + <kp>1e+5</kp> |
| 119 | + <kd>1</kd> |
| 120 | + <max_vel>0.01</max_vel> |
| 121 | + <min_depth>0.001</min_depth> |
| 122 | + </ode> |
| 123 | + </contact> |
| 124 | + </surface> |
| 125 | + </gazebo> |
| 126 | + </collision> |
| 127 | + <visual > |
| 128 | + <origin rpy="0 0 0" xyz="0.0 -0.144 0.023"/> |
| 129 | + <geometry> |
| 130 | + <mesh filename="$(find custom_robots)/model/urtlebot3/meshes/tire.dae" scale="0.001 0.001 0.001"/> |
| 131 | + </geometry> |
| 132 | + <gazebo> |
| 133 | + <material> |
| 134 | + <ambient>1 1 1 1</ambient> |
| 135 | + <diffuse>1 1 1 1</diffuse> |
| 136 | + <specular>0.2 0.2 0.2 1</specular> |
| 137 | + <emissive>0 0 0 1</emissive> |
| 138 | + </material> |
| 139 | + </gazebo> |
| 140 | + </visual> |
| 141 | + </link> |
| 142 | + |
| 143 | + <link name="caster_back_right_link"> |
| 144 | + <origin rpy="-1.57 0 0" xyz="-0.177 -0.064 -0.004"/> |
| 145 | + <inertial> |
| 146 | + <mass value="0.001"/> |
| 147 | + <inertia ixx="0.00001" ixy="0" ixz="0" iyy="0.00001" iyz="0" izz="0.00001"/> |
| 148 | + </inertial> |
| 149 | + <collision> |
| 150 | + <geometry> |
| 151 | + <sphere radius="0.005"/> |
| 152 | + </geometry> |
| 153 | + <gazebo> |
| 154 | + <surface> |
| 155 | + <contact> |
| 156 | + <ode> |
| 157 | + <soft_cfm>0</soft_cfm> |
| 158 | + <soft_erp>0.2</soft_erp> |
| 159 | + <kp>1e+5</kp> |
| 160 | + <kd>1</kd> |
| 161 | + <max_vel>0.01</max_vel> |
| 162 | + <min_depth>0.001</min_depth> |
| 163 | + </ode> |
| 164 | + </contact> |
| 165 | + </surface> |
| 166 | + </gazebo> |
| 167 | + </collision> |
| 168 | + </link> |
| 169 | + |
| 170 | + <link name="caster_back_left_link"> |
| 171 | + <origin rpy="-1.57 0 0" xyz="-0.177 0.064 -0.004"/> |
| 172 | + <inertial> |
| 173 | + <mass value="0.001"/> |
| 174 | + <inertia ixx="0.00001" ixy="0" ixz="0" iyy="0.00001" iyz="0" izz="0.00001"/> |
| 175 | + </inertial> |
| 176 | + <collision> |
| 177 | + <geometry> |
| 178 | + <sphere radius="0.005"/> |
| 179 | + </geometry> |
| 180 | + <gazebo> |
| 181 | + <surface> |
| 182 | + <contact> |
| 183 | + <ode> |
| 184 | + <soft_cfm>0</soft_cfm> |
| 185 | + <soft_erp>0.2</soft_erp> |
| 186 | + <kp>1e+5</kp> |
| 187 | + <kd>1</kd> |
| 188 | + <max_vel>0.01</max_vel> |
| 189 | + <min_depth>0.001</min_depth> |
| 190 | + </ode> |
| 191 | + </contact> |
| 192 | + </surface> |
| 193 | + </gazebo> |
| 194 | + </collision> |
| 195 | + </link> |
| 196 | + |
| 197 | + <link name="camera_link"/> |
| 198 | + |
| 199 | + <joint name="base_to_base_link" type="fixed"> |
| 200 | + <parent link="base_footprint"/> |
| 201 | + <child link="base_link"/> |
| 202 | + <origin xyz="0 0 0.01" rpy="0 0 0"/> |
| 203 | + <axis xyz="0 0 1"/> |
| 204 | + </joint> |
| 205 | + |
| 206 | + <joint name="camera_joint" type="fixed"> |
| 207 | + <parent link="base_link"/> |
| 208 | + <child link="camera_link"/> |
| 209 | + <origin xyz="0.064 -0.065 0.094" rpy="0 0 0"/> |
| 210 | + <axis xyz="0 0 1"/> |
| 211 | + </joint> |
| 212 | + |
| 213 | + <joint name="wheel_left_joint" type="continuous"> |
| 214 | + <origin rpy="-1.57 0 0" xyz="0.0 0.144 0.023"/> |
| 215 | + <parent link="base_link"/> |
| 216 | + <child link="wheel_left_link"/> |
| 217 | + <axis xyz="0 0 1"/> |
| 218 | + <limit effort="20" velocity="100"/> |
| 219 | + </joint> |
| 220 | + |
| 221 | + <joint name="wheel_right_joint" type="continuous"> |
| 222 | + <origin rpy="-1.57 0 0" xyz="0.0 -0.144 0.023"/> |
| 223 | + <parent link="base_link"/> |
| 224 | + <child link="wheel_right_link"/> |
| 225 | + <axis xyz="0 0 1"/> |
| 226 | + <limit effort="20" velocity="100"/> |
| 227 | + </joint> |
| 228 | + |
| 229 | + <!-- Ball joints --> |
| 230 | + <joint name="caster_back_right_joint" type="continuous"> |
| 231 | + <parent link="base_link"/> |
| 232 | + <child link="caster_back_right_link"/> |
| 233 | + <limit effort="20" velocity="100"/> |
| 234 | + </joint> |
| 235 | + |
| 236 | + <joint name="caster_back_left_joint" type="continuous"> |
| 237 | + <parent link="base_link"/> |
| 238 | + <child link="caster_back_left_link"/> |
| 239 | + <limit effort="20" velocity="100"/> |
| 240 | + </joint> |
| 241 | + |
| 242 | + <xacro:imu parent="imu_link" topic="turtlebot3/imu" xyz="-0.032 0 0.068" rpy="0 0 0"/> |
| 243 | + <xacro:lidar xyz="-0.064 0 0.121" rpy="0 0 0" name="lidar" parent="base_link" topic="turtlebot3/laser/scan"/> |
| 244 | + <xacro:velocity topic="turtlebot3/cmd_vel"/> |
| 245 | + <xacro:odom topic="/turtlebot3/odom" freq="50"/> |
| 246 | + </xacro:macro> |
| 247 | +</robot> |
0 commit comments