|
326 | 326 | <axis xyz="0 0 1"/>
|
327 | 327 | <limit effort="87" lower="-3.0718" upper="-0.0698" velocity="2.1750" drake:acceleration="12.5"/>
|
328 | 328 | </joint>
|
329 |
| - <link name="panda_link5_lower"> |
| 329 | + <link name="panda_link5"> |
330 | 330 | <inertial>
|
331 | 331 | <mass value="2.74"/>
|
332 | 332 | <origin xyz="0 0.0610427 -0.104176" rpy="0 0 0"/>
|
|
350 | 350 | <sphere radius="0.06"/>
|
351 | 351 | </geometry>
|
352 | 352 | </collision>
|
| 353 | + <collision> |
| 354 | + <origin rpy="0 0 0" xyz="0.0 0.09 -0.055"/> |
| 355 | + <geometry> |
| 356 | + <sphere radius="0.035"/> |
| 357 | + </geometry> |
| 358 | + </collision> |
353 | 359 | <collision>
|
354 | 360 | <origin rpy="0 0 0" xyz="0.0 0.0850 -0.08"/>
|
355 | 361 | <geometry>
|
|
381 | 387 | </geometry>
|
382 | 388 | </collision>
|
383 | 389 | <collision>
|
384 |
| - <origin rpy="0 0 0" xyz="0.0 0.05 -0.20"/> |
385 |
| - <geometry> |
386 |
| - <sphere radius="0.055"/> |
387 |
| - </geometry> |
388 |
| - </collision> |
389 |
| - </link> |
390 |
| - <joint name="panda_joint5" type="revolute"> |
391 |
| - <origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/> |
392 |
| - <parent link="panda_link4"/> |
393 |
| - <child link="panda_link5_lower"/> |
394 |
| - <axis xyz="0 0 1"/> |
395 |
| - <limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.610" drake:acceleration="15.0"/> |
396 |
| - </joint> |
397 |
| - <link name="panda_link5_upper"> |
398 |
| - <collision> |
399 |
| - <origin rpy="0 0 0" xyz="0.0 0.09 -0.055"/> |
| 390 | + <origin rpy="0 0 0" xyz="0.0 0.08 -0.02"/> |
400 | 391 | <geometry>
|
401 |
| - <sphere radius="0.035"/> |
| 392 | + <sphere radius="0.05"/> |
402 | 393 | </geometry>
|
403 | 394 | </collision>
|
404 | 395 | <collision>
|
405 |
| - <origin rpy="0 0 0" xyz="0.0 0.08 -0.02"/> |
| 396 | + <origin rpy="0 0 0" xyz="0.0 0.08 -0.0"/> |
406 | 397 | <geometry>
|
407 |
| - <sphere radius="0.05"/> |
| 398 | + <sphere radius="0.055"/> |
408 | 399 | </geometry>
|
409 | 400 | </collision>
|
410 | 401 | <collision>
|
411 |
| - <origin rpy="0 0 0" xyz="0.0 0.08 0.0"/> |
| 402 | + <origin rpy="0 0 0" xyz="0.0 0.05 -0.20"/> |
412 | 403 | <geometry>
|
413 | 404 | <sphere radius="0.055"/>
|
414 | 405 | </geometry>
|
415 | 406 | </collision>
|
416 | 407 | <collision>
|
417 |
| - <origin rpy="0 0 0" xyz="0.0 0.07 0.0"/> |
| 408 | + <origin rpy="0 0 0" xyz="0.0 0.07 -0.0"/> |
418 | 409 | <geometry>
|
419 | 410 | <sphere radius="0.06"/>
|
420 | 411 | </geometry>
|
421 | 412 | </collision>
|
422 | 413 | </link>
|
423 |
| - <joint name="panda_joint5_lower_upper" type="fixed"> |
424 |
| - <origin rpy="0 0 0" xyz="0 0 0"/> |
425 |
| - <parent link="panda_link5_lower"/> |
426 |
| - <child link="panda_link5_upper"/> |
| 414 | + <joint name="panda_joint5" type="revolute"> |
| 415 | + <origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/> |
| 416 | + <parent link="panda_link4"/> |
| 417 | + <child link="panda_link5"/> |
| 418 | + <axis xyz="0 0 1"/> |
| 419 | + <limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.610" drake:acceleration="15.0"/> |
427 | 420 | </joint>
|
428 | 421 | <link name="panda_link6">
|
429 | 422 | <inertial>
|
|
470 | 463 | </link>
|
471 | 464 | <joint name="panda_joint6" type="revolute">
|
472 | 465 | <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
473 |
| - <parent link="panda_link5_upper"/> |
| 466 | + <parent link="panda_link5"/> |
474 | 467 | <child link="panda_link6"/>
|
475 | 468 | <axis xyz="0 0 1"/>
|
476 | 469 | <limit effort="12" lower="-0.0175" upper="3.7525" velocity="2.610" drake:acceleration="20.0"/>
|
|
604 | 597 | <drake:rotor_inertia value="0.0000205544064" />
|
605 | 598 | </actuator>
|
606 | 599 | </transmission>
|
607 |
| - <drake:collision_filter_group name="group_link0123"> |
608 |
| - <drake:member link="panda_link0"/> |
609 |
| - <drake:member link="panda_link1"/> |
610 |
| - <drake:member link="panda_link2"/> |
611 |
| - <drake:member link="panda_link3"/> |
612 |
| - <drake:ignored_collision_filter_group name="group_link0123"/> |
613 |
| - </drake:collision_filter_group> |
614 |
| - <drake:collision_filter_group name="group_link1234"> |
615 |
| - <drake:member link="panda_link1"/> |
616 |
| - <drake:member link="panda_link2"/> |
617 |
| - <drake:member link="panda_link3"/> |
618 |
| - <drake:member link="panda_link4"/> |
619 |
| - <drake:ignored_collision_filter_group name="group_link1234"/> |
620 |
| - </drake:collision_filter_group> |
621 |
| - <!-- TODO(calderpg-tri) See if this group could be extended to 345678. --> |
622 |
| - <drake:collision_filter_group name="group_link3456"> |
623 |
| - <drake:member link="panda_link3"/> |
624 |
| - <drake:member link="panda_link4"/> |
625 |
| - <drake:member link="panda_link5_lower"/> |
626 |
| - <drake:member link="panda_link5_upper"/> |
627 |
| - <drake:member link="panda_link6"/> |
628 |
| - <drake:ignored_collision_filter_group name="group_link3456"/> |
629 |
| - </drake:collision_filter_group> |
630 |
| - <drake:collision_filter_group name="group_link567"> |
631 |
| - <drake:member link="panda_link5_lower"/> |
632 |
| - <drake:member link="panda_link5_upper"/> |
633 |
| - <drake:member link="panda_link6"/> |
| 600 | + <drake:collision_filter_group name="group_link57"> |
| 601 | + <drake:member link="panda_link5"/> |
634 | 602 | <drake:member link="panda_link7"/>
|
635 |
| - <drake:ignored_collision_filter_group name="group_link567"/> |
| 603 | + <drake:ignored_collision_filter_group name="group_link57"/> |
636 | 604 | </drake:collision_filter_group>
|
637 |
| - <drake:collision_filter_group name="group_link5upper678"> |
638 |
| - <drake:member link="panda_link5_upper"/> |
| 605 | + <drake:collision_filter_group name="group_link68"> |
639 | 606 | <drake:member link="panda_link6"/>
|
640 |
| - <drake:member link="panda_link7"/> |
641 | 607 | <drake:member link="panda_link8"/>
|
642 |
| - <drake:ignored_collision_filter_group name="group_link5upper678"/> |
| 608 | + <drake:ignored_collision_filter_group name="group_link68"/> |
643 | 609 | </drake:collision_filter_group>
|
644 | 610 | </robot>
|
0 commit comments