1<?xml version="1.0" ?> 2<robot name="mini_cheetah" xmlns:xacro="http://ros.org/wiki/xacro"> 3 <link name="body"> 4 <inertial> 5 <mass value="3.3"/> 6 <origin xyz="0.0 0.0 0.0"/> 7 <inertia ixx="0.011253" ixy="0" ixz="0" iyy="0.036203" iyz="0" izz="0.042673"/> 8 </inertial> 9 <visual> 10 <geometry> 11 <mesh filename="meshes/mini_body.obj"/> 12 </geometry> 13 <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/> 14 </visual> 15 <collision> 16 <geometry> 17 <mesh filename="meshes/mini_body.obj"/> 18 </geometry> 19 <origin rpy="0 0 0" xyz="0 0 0"/> 20 </collision> 21 </link> 22 23 <!--!!!!!!!!!!!! Front Right Leg !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!--> 24 <joint name="torso_to_abduct_fr_j" type="continuous"> 25 <axis xyz="1 0 0"/> 26 <origin rpy="0 0 0" xyz="0.19 -0.049 0.0"/> 27 <parent link="body"/> 28 <child link="abduct_fr"/> 29 </joint> 30 <link name="abduct_fr"> 31 <inertial> 32 <mass value="0.54"/> 33 <origin xyz="0.0 0.036 0."/> 34 <inertia ixx="0.000381" ixy="0.000058" ixz="0.00000045" 35 iyy="0.000560" iyz="0.00000095" izz="0.000444"/> 36 </inertial> 37 <visual> 38 <geometry> 39 <mesh filename="meshes/mini_abad.obj"/> 40 </geometry> 41 <origin rpy="3.141592 0.0 1.5708" xyz="-0.055 0.0 0.0"/> 42 </visual> 43 <collision> 44 <geometry> 45 <mesh filename="meshes/mini_abad.obj"/> 46 </geometry> 47 <origin rpy="3.141592 0 1.5708" xyz="-0.055 0 0"/> 48 </collision> 49 </link> 50 51 <joint name="abduct_fr_to_thigh_fr_j" type="continuous"> 52 <axis xyz="0 -1 0"/> 53 <origin rpy="0.0 0.0 0.0" xyz="0.0 -0.062 0.00"/> 54 <parent link="abduct_fr"/> 55 <child link="thigh_fr"/> 56 </joint> 57 <link name="thigh_fr"> 58 <inertial> 59 <mass value="0.634"/> 60 <origin xyz="0.0 0.016 -0.02"/> 61 <inertia ixx="0.001983" ixy="0.000245" ixz="0.000013" 62 iyy="0.002103" iyz="0.0000015" izz="0.000408"/> 63 </inertial> 64 <visual> 65 <geometry> 66 <mesh filename="meshes/mini_upper_link.obj"/> 67 </geometry> 68 <origin rpy="0.0 -1.5708 0.0" xyz="0.0 0.0 0.0"/> 69 </visual> 70 <collision> 71 <geometry> 72 <mesh filename="meshes/mini_upper_link.obj"/> 73 </geometry> 74 <origin rpy="0 -1.5708 0" xyz="0 0 0"/> 75 </collision> 76 </link> 77 78 <joint name="thigh_fr_to_knee_fr_j" type="continuous"> 79 <axis xyz="0 -1 0"/> 80 <origin rpy="0.0 0 0.0" xyz="0.0 0.0 -0.209"/> 81 <parent link="thigh_fr"/> 82 <child link="shank_fr"/> 83 </joint> 84 <link name="shank_fr"> 85 <inertial> 86 <mass value="0.064"/> 87 <origin xyz="0.0 0.0 -0.209"/> 88 <inertia ixx="0.000245" ixy="0" ixz="0.0" iyy="0.000248" iyz="0" izz="0.000006"/> 89 </inertial> 90 <visual> 91 <geometry> 92 <mesh filename="meshes/mini_lower_link.obj"/> 93 </geometry> 94 <origin rpy="0.0 3.141592 0.0" xyz="0.0 0.0 0.0"/> 95 </visual> 96 <collision> 97 <geometry> 98 <mesh filename="meshes/mini_lower_link.obj"/> 99 </geometry> 100 <origin rpy="0 3.141592 0" xyz="0 0 0"/> 101 </collision> 102 </link> 103 <link name="toe_fr"> 104 <contact> 105 <friction_anchor/> 106 <stiffness value="30000.0"/> 107 <damping value="1000.0"/> 108 <spinning_friction value="0.3"/> 109 <lateral_friction value="3.0"/> 110 </contact> 111 <visual> 112 <origin rpy="0 0 0" xyz="0 0 0"/> 113 <geometry> 114 <sphere radius="0.015"/> 115 </geometry> 116 <material name="darkgray"/> 117 </visual> 118 <collision> 119 <origin rpy="0 0 0" xyz="0 0 0"/> 120 <geometry> 121 <sphere radius="0.015"/> 122 </geometry> 123 </collision> 124 <inertial> 125 <mass value="0.15"/> 126 <inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/> 127 </inertial> 128 </link> 129 <joint name="toe_fr_joint" type="fixed"> 130 <parent link="shank_fr"/> 131 <child link="toe_fr"/> 132 <origin xyz="0 0 -0.18"/> 133 <dynamics damping="0.0" friction="0.0"/> 134 </joint> 135 136 137<!--!!!!!!!!!!!! Front Left Leg !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!--> 138 <joint name="torso_to_abduct_fl_j" type="continuous"> 139 <axis xyz="1 0 0"/> 140 <origin rpy="0 0 0" xyz="0.19 0.049 0.0"/> 141 <parent link="body"/> 142 <child link="abduct_fl"/> 143 </joint> 144 <link name="abduct_fl"> 145 <inertial> 146 <mass value="0.54"/> 147 <origin xyz="0.0 0.036 0."/> 148 <inertia ixx="0.000381" ixy="0.000058" ixz="0.00000045" 149 iyy="0.000560" iyz="0.00000095" izz="0.000444"/> 150 </inertial> 151 <visual> 152 <geometry> 153 <mesh filename="meshes/mini_abad.obj"/> 154 </geometry> 155 <origin rpy="0. 0. -1.5708" xyz="-0.055 0.0 0.0"/> 156 </visual> 157 <collision> 158 <geometry> 159 <mesh filename="meshes/mini_abad.obj"/> 160 </geometry> 161 <origin rpy="0 0 -1.5708" xyz="-0.055 0 0"/> 162 </collision> 163 </link> 164 165 <joint name="abduct_fl_to_thigh_fl_j" type="continuous"> 166 <axis xyz="0 -1 0"/> 167 <origin rpy="0.0 0.0 0.0" xyz="0.0 0.062 0.00"/> 168 <parent link="abduct_fl"/> 169 <child link="thigh_fl"/> 170 </joint> 171 <link name="thigh_fl"> 172 <inertial> 173 <mass value="0.634"/> 174 <origin xyz="0.0 0.016 -0.02"/> 175 <inertia ixx="0.001983" ixy="0.000245" ixz="0.000013" 176 iyy="0.002103" iyz="0.0000015" izz="0.000408"/> 177 </inertial> 178 <visual> 179 <geometry> 180 <mesh filename="meshes/mini_upper_link.obj"/> 181 </geometry> 182 <origin rpy="0.0 -1.5708 0.0" xyz="0.0 0.0 0.0"/> 183 </visual> 184 <collision> 185 <geometry> 186 <mesh filename="meshes/mini_upper_link.obj"/> 187 </geometry> 188 <origin rpy="0 -1.5708 0" xyz="0 0 0"/> 189 </collision> 190 </link> 191 192 <joint name="thigh_fl_to_knee_fl_j" type="continuous"> 193 <axis xyz="0 -1 0"/> 194 <origin rpy="0.0 0 0.0" xyz="0.0 0.0 -0.209"/> 195 <parent link="thigh_fl"/> 196 <child link="shank_fl"/> 197 </joint> 198 <link name="shank_fl"> 199 <inertial> 200 <mass value="0.064"/> 201 <origin xyz="0.0 0.0 -0.209"/> 202 <inertia ixx="0.000245" ixy="0" ixz="0.0" iyy="0.000248" iyz="0" izz="0.000006"/> 203 </inertial> 204 <visual> 205 <geometry> 206 <mesh filename="meshes/mini_lower_link.obj"/> 207 </geometry> 208 <origin rpy="0.0 3.141592 0.0" xyz="0.0 0.0 0.0"/> 209 </visual> 210 <collision> 211 <geometry> 212 <mesh filename="meshes/mini_lower_link.obj"/> 213 </geometry> 214 <origin rpy="0 3.141592 0" xyz="0 0 0"/> 215 </collision> 216 </link> 217 <link name="toe_fl"> 218 <contact> 219 <friction_anchor/> 220 <stiffness value="30000.0"/> 221 <damping value="1000.0"/> 222 <spinning_friction value="0.3"/> 223 <lateral_friction value="3.0"/> 224 </contact> 225 <visual> 226 <origin rpy="0 0 0" xyz="0 0 0"/> 227 <geometry> 228 <sphere radius="0.015"/> 229 </geometry> 230 <material name="darkgray"/> 231 </visual> 232 <collision> 233 <origin rpy="0 0 0" xyz="0 0 0"/> 234 <geometry> 235 <sphere radius="0.015"/> 236 </geometry> 237 </collision> 238 <inertial> 239 <mass value="0.15"/> 240 <inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/> 241 </inertial> 242 </link> 243 <joint name="toe_fl_joint" type="fixed"> 244 <parent link="shank_fl"/> 245 <child link="toe_fl"/> 246 <origin xyz="0 0 -0.18"/> 247 <dynamics damping="0.0" friction="0.0"/> 248 </joint> 249 250 251<!--!!!!!!!!!!!! Hind Right Leg !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!--> 252 <joint name="torso_to_abduct_hr_j" type="continuous"> 253 <axis xyz="1 0 0"/> 254 <origin rpy="0 0 0" xyz="-0.19 -0.049 0.0"/> 255 <parent link="body"/> 256 <child link="abduct_hr"/> 257 </joint> 258 <link name="abduct_hr"> 259 <inertial> 260 <mass value="0.54"/> 261 <origin xyz="0.0 0.036 0."/> 262 <inertia ixx="0.000381" ixy="0.000058" ixz="0.00000045" 263 iyy="0.000560" iyz="0.00000095" izz="0.000444"/> 264 </inertial> 265 <visual> 266 <geometry> 267 <mesh filename="meshes/mini_abad.obj"/> 268 </geometry> 269 <origin rpy="0.0 0.0 1.5708" xyz="0.055 0.0 0.0"/> 270 </visual> 271 <collision> 272 <geometry> 273 <mesh filename="meshes/mini_abad.obj"/> 274 </geometry> 275 <origin rpy="0 0 1.5708" xyz="0.055 0 0"/> 276 </collision> 277 </link> 278 279 <joint name="abduct_hr_to_thigh_hr_j" type="continuous"> 280 <axis xyz="0 -1 0"/> 281 <origin rpy="0.0 0.0 0.0" xyz="0.0 -0.062 0.00"/> 282 <parent link="abduct_hr"/> 283 <child link="thigh_hr"/> 284 </joint> 285 <link name="thigh_hr"> 286 <inertial> 287 <mass value="0.634"/> 288 <origin xyz="0.0 0.016 -0.02"/> 289 <inertia ixx="0.001983" ixy="0.000245" ixz="0.000013" 290 iyy="0.002103" iyz="0.0000015" izz="0.000408"/> 291 </inertial> 292 <visual> 293 <geometry> 294 <mesh filename="meshes/mini_upper_link.obj"/> 295 </geometry> 296 <origin rpy="0.0 -1.5708 0.0" xyz="0.0 0.0 0.0"/> 297 </visual> 298 <collision> 299 <geometry> 300 <mesh filename="meshes/mini_upper_link.obj"/> 301 </geometry> 302 <origin rpy="0 -1.5708 0" xyz="0 0 0"/> 303 </collision> 304 </link> 305 306 <joint name="thigh_hr_to_knee_hr_j" type="continuous"> 307 <axis xyz="0 -1 0"/> 308 <origin rpy="0.0 0 0.0" xyz="0.0 0.0 -0.209"/> 309 <parent link="thigh_hr"/> 310 <child link="shank_hr"/> 311 </joint> 312 <link name="shank_hr"> 313 <inertial> 314 <mass value="0.064"/> 315 <origin xyz="0.0 0.0 -0.209"/> 316 <inertia ixx="0.000245" ixy="0" ixz="0.0" iyy="0.000248" iyz="0" izz="0.000006"/> 317 </inertial> 318 <visual> 319 <geometry> 320 <mesh filename="meshes/mini_lower_link.obj"/> 321 </geometry> 322 <origin rpy="0.0 3.141592 0.0" xyz="0.0 0.0 0.0"/> 323 </visual> 324 <collision> 325 <geometry> 326 <mesh filename="meshes/mini_lower_link.obj"/> 327 </geometry> 328 <origin rpy="0 3.141592 0" xyz="0 0 0"/> 329 </collision> 330 </link> 331 <link name="toe_hr"> 332 <contact> 333 <friction_anchor/> 334 <stiffness value="30000.0"/> 335 <damping value="1000.0"/> 336 <spinning_friction value="0.3"/> 337 <lateral_friction value="3.0"/> 338 </contact> 339 <visual> 340 <origin rpy="0 0 0" xyz="0 0 0"/> 341 <geometry> 342 <sphere radius="0.015"/> 343 </geometry> 344 <material name="darkgray"/> 345 </visual> 346 <collision> 347 <origin rpy="0 0 0" xyz="0 0 0"/> 348 <geometry> 349 <sphere radius="0.015"/> 350 </geometry> 351 </collision> 352 <inertial> 353 <mass value="0.15"/> 354 <inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/> 355 </inertial> 356 </link> 357 <joint name="toe_hr_joint" type="fixed"> 358 <parent link="shank_hr"/> 359 <child link="toe_hr"/> 360 <origin xyz="0 0 -0.18"/> 361 <dynamics damping="0.0" friction="0.0"/> 362 </joint> 363 364 365<!--!!!!!!!!!!!! Hind Left Leg !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!--> 366 <joint name="torso_to_abduct_hl_j" type="continuous"> 367 <axis xyz="1 0 0"/> 368 <origin rpy="0 0 0" xyz="-0.19 0.049 0.0"/> 369 <parent link="body"/> 370 <child link="abduct_hl"/> 371 </joint> 372 <link name="abduct_hl"> 373 <inertial> 374 <mass value="0.54"/> 375 <origin xyz="0.0 0.036 0."/> 376 <inertia ixx="0.000381" ixy="0.000058" ixz="0.00000045" 377 iyy="0.000560" iyz="0.00000095" izz="0.000444"/> 378 </inertial> 379 <visual> 380 <geometry> 381 <mesh filename="meshes/mini_abad.obj"/> 382 </geometry> 383 <origin rpy="3.141592 0.0 -1.5708" xyz="0.055 0.0 0.0"/> 384 </visual> 385 <collision> 386 <geometry> 387 <mesh filename="meshes/mini_abad.obj"/> 388 </geometry> 389 <origin rpy="3.141592 0 -1.5708" xyz="0.055 0 0"/> 390 </collision> 391 </link> 392 393 <joint name="abduct_hl_to_thigh_hl_j" type="continuous"> 394 <axis xyz="0 -1 0"/> 395 <origin rpy="0.0 0.0 0.0" xyz="0.0 0.062 0.00"/> 396 <parent link="abduct_hl"/> 397 <child link="thigh_hl"/> 398 </joint> 399 <link name="thigh_hl"> 400 <inertial> 401 <mass value="0.634"/> 402 <origin xyz="0.0 0.016 -0.02"/> 403 <inertia ixx="0.001983" ixy="0.000245" ixz="0.000013" 404 iyy="0.002103" iyz="0.0000015" izz="0.000408"/> 405 </inertial> 406 <visual> 407 <geometry> 408 <mesh filename="meshes/mini_upper_link.obj"/> 409 </geometry> 410 <origin rpy="0.0 -1.5708 0.0" xyz="0.0 0.0 0.0"/> 411 </visual> 412 <collision> 413 <geometry> 414 <mesh filename="meshes/mini_upper_link.obj"/> 415 </geometry> 416 <origin rpy="0 -1.5708 0" xyz="0 0 0"/> 417 </collision> 418 </link> 419 420 <joint name="thigh_hl_to_knee_hl_j" type="continuous"> 421 <axis xyz="0 -1 0"/> 422 <origin rpy="0.0 0 0.0" xyz="0.0 0.0 -0.209"/> 423 <parent link="thigh_hl"/> 424 <child link="shank_hl"/> 425 </joint> 426 <link name="shank_hl"> 427 <inertial> 428 <mass value="0.064"/> 429 <origin xyz="0.0 0.0 -0.209"/> 430 <inertia ixx="0.000245" ixy="0" ixz="0.0" iyy="0.000248" iyz="0" izz="0.000006"/> 431 </inertial> 432 <visual> 433 <geometry> 434 <mesh filename="meshes/mini_lower_link.obj"/> 435 </geometry> 436 <origin rpy="0.0 3.141592 0.0" xyz="0.0 0.0 0.0"/> 437 </visual> 438 <collision> 439 <geometry> 440 <mesh filename="meshes/mini_lower_link.obj"/> 441 </geometry> 442 <origin rpy="0 3.141592 0" xyz="0 0 0"/> 443 </collision> 444 </link> 445 <link name="toe_hl"> 446 <contact> 447 <friction_anchor/> 448 <stiffness value="30000.0"/> 449 <damping value="1000.0"/> 450 <spinning_friction value="0.3"/> 451 <lateral_friction value="3.0"/> 452 </contact> 453 <visual> 454 <origin rpy="0 0 0" xyz="0 0 0"/> 455 <geometry> 456 <sphere radius="0.015"/> 457 </geometry> 458 <material name="darkgray"/> 459 </visual> 460 <collision> 461 <origin rpy="0 0 0" xyz="0 0 0"/> 462 <geometry> 463 <sphere radius="0.015"/> 464 </geometry> 465 </collision> 466 <inertial> 467 <mass value="0.15"/> 468 <inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/> 469 </inertial> 470 </link> 471 <joint name="toe_hl_joint" type="fixed"> 472 <parent link="shank_hl"/> 473 <child link="toe_hl"/> 474 <origin xyz="0 0 -0.18"/> 475 <dynamics damping="0.0" friction="0.0"/> 476 </joint> 477 478 479 480</robot> 481