| |
| |
| |
| |
| |
| |
| |
|
|
| |
| |
|
|
| api_version: 1.0 |
|
|
| |
| |
| |
| cspace: |
| - panda_joint1 |
| - panda_joint2 |
| - panda_joint3 |
| - panda_joint4 |
| - panda_joint5 |
| - panda_joint6 |
| - panda_joint7 |
|
|
| root_link: base_link |
|
|
| default_q: [ |
| |
| |
|
|
| |
| 0.00, -1.3, 0.00, -2.87, 0.00, 2.00, 0.75 |
| ] |
|
|
| acceleration_limits: [15.0, 7.5, 10.0, 12.5, 15.0, 20.0, 20.0] |
| jerk_limits: [7500.0, 3750.0, 5000.0, 6250.0, 7500.0, 10000.0, 10000.0] |
|
|
| |
| |
| |
| cspace_to_urdf_rules: |
| - {name: panda_finger_joint1, rule: fixed, value: 0.025} |
| - {name: panda_finger_joint2, rule: fixed, value: 0.025} |
|
|
| collision_spheres: |
| - panda_link0: |
| - "center": [0.0, 0.0, 0.05] |
| "radius": 0.045 |
| - panda_link1: |
| - "center": [0.0, -0.08, 0.0] |
| "radius": 0.06 |
| - "center": [0.0, -0.03, 0.0] |
| "radius": 0.06 |
| - "center": [0.0, 0.0, -0.12] |
| "radius": 0.06 |
| - "center": [0.0, 0.0, -0.17] |
| "radius": 0.06 |
| - panda_link2: |
| - "center": [0.0, 0.0, 0.03] |
| "radius": 0.06 |
| - "center": [0.0, 0.0, 0.08] |
| "radius": 0.06 |
| - "center": [0.0, -0.12, 0.0] |
| "radius": 0.06 |
| - "center": [0.0, -0.17, 0.0] |
| "radius": 0.06 |
| - panda_link3: |
| - "center": [0.0, 0.0, -0.06] |
| "radius": 0.05 |
| - "center": [0.0, 0.0, -0.1] |
| "radius": 0.06 |
| - "center": [0.08, 0.06, 0.0] |
| "radius": 0.055 |
| - "center": [0.08, 0.02, 0.0] |
| "radius": 0.055 |
| - panda_link4: |
| - "center": [0.0, 0.0, 0.02] |
| "radius": 0.055 |
| - "center": [0.0, 0.0, 0.06] |
| "radius": 0.055 |
| - "center": [-0.08, 0.095, 0.0] |
| "radius": 0.06 |
| - "center": [-0.08, 0.06, 0.0] |
| "radius": 0.055 |
| - panda_link5: |
| - "center": [0.0, 0.055, 0.0] |
| "radius": 0.06 |
| - "center": [0.0, 0.075, 0.0] |
| "radius": 0.06 |
| - "center": [0.0, 0.000, -0.22] |
| "radius": 0.06 |
| - "center": [0.0, 0.05, -0.18] |
| "radius": 0.05 |
| - "center": [0.01, 0.08, -0.14] |
| "radius": 0.025 |
| - "center": [0.01, 0.085, -0.11] |
| "radius": 0.025 |
| - "center": [0.01, 0.09, -0.08] |
| "radius": 0.025 |
| - "center": [0.01, 0.095, -0.05] |
| "radius": 0.025 |
| - "center": [-0.01, 0.08, -0.14] |
| "radius": 0.025 |
| - "center": [-0.01, 0.085, -0.11] |
| "radius": 0.025 |
| - "center": [-0.01, 0.09, -0.08] |
| "radius": 0.025 |
| - "center": [-0.01, 0.095, -0.05] |
| "radius": 0.025 |
| - panda_link6: |
| - "center": [0.0, 0.0, 0.0] |
| "radius": 0.06 |
| - "center": [0.08, 0.03, 0.0] |
| "radius": 0.06 |
| - "center": [0.08, -0.01, 0.0] |
| "radius": 0.06 |
| - panda_link7: |
| - "center": [0.0, 0.0, 0.07] |
| "radius": 0.05 |
| - "center": [0.02, 0.04, 0.08] |
| "radius": 0.025 |
| - "center": [0.04, 0.02, 0.08] |
| "radius": 0.025 |
| - "center": [0.04, 0.06, 0.085] |
| "radius": 0.02 |
| - "center": [0.06, 0.04, 0.085] |
| "radius": 0.02 |
| - panda_hand: |
| - "center": [0.0, -0.075, 0.01] |
| "radius": 0.028 |
| - "center": [0.0, -0.045, 0.01] |
| "radius": 0.028 |
| - "center": [0.0, -0.015, 0.01] |
| "radius": 0.028 |
| - "center": [0.0, 0.015, 0.01] |
| "radius": 0.028 |
| - "center": [0.0, 0.045, 0.01] |
| "radius": 0.028 |
| - "center": [0.0, 0.075, 0.01] |
| "radius": 0.028 |
| - "center": [0.0, -0.075, 0.03] |
| "radius": 0.026 |
| - "center": [0.0, -0.045, 0.03] |
| "radius": 0.026 |
| - "center": [0.0, -0.015, 0.03] |
| "radius": 0.026 |
| - "center": [0.0, 0.015, 0.03] |
| "radius": 0.026 |
| - "center": [0.0, 0.045, 0.03] |
| "radius": 0.026 |
| - "center": [0.0, 0.075, 0.03] |
| "radius": 0.026 |
| - "center": [0.0, -0.075, 0.05] |
| "radius": 0.024 |
| - "center": [0.0, -0.045, 0.05] |
| "radius": 0.024 |
| - "center": [0.0, -0.015, 0.05] |
| "radius": 0.024 |
| - "center": [0.0, 0.015, 0.05] |
| "radius": 0.024 |
| - "center": [0.0, 0.045, 0.05] |
| "radius": 0.024 |
| - "center": [0.0, 0.075, 0.05] |
| "radius": 0.024 |