anymal.srdf 5.8 KB
Newer Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
<?xml version="1.0" ?>
<robot name="anymal">

    <group name="lf_leg">
        <joint name="LF_HAA" />
        <joint name="LF_HFE" />
        <joint name="LF_KFE" />
        <chain base_link="base" tip_link="LF_FOOT" />
    </group>
    <group name="lh_leg">
        <joint name="LH_HAA" />
        <joint name="LH_HFE" />
        <joint name="LH_KFE" />
        <chain base_link="base" tip_link="LH_FOOT" />
    </group>
    <group name="rf_leg">
        <joint name="RF_HAA" />
        <joint name="RF_HFE" />
        <joint name="RF_KFE" />
        <chain base_link="base" tip_link="RF_FOOT" />
    </group>
    <group name="rh_leg">
        <joint name="RH_HAA" />
        <joint name="RH_HFE" />
        <joint name="RH_KFE" />
        <chain base_link="base" tip_link="RH_FOOT" />
    </group>
    <group name="all_legs">
        <group name="lf" />
        <group name="rf" />
        <group name="lh" />
        <group name="rh" />
    </group>
    <group name="r_legs">
        <group name="rf" />
        <group name="rh" />
    </group>
    <group name="l_legs">
        <group name="lf" />
        <group name="lh" />
    </group>
    <group name="f_legs">
        <group name="lf" />
        <group name="rf" />
    </group>
    <group name="h_legs">
        <group name="lh" />
        <group name="rh" />
    </group>
    <group name="ld_legs">
        <group name="lf" />
        <group name="rh" />
    </group>
    <group name="rd_legs">
        <group name="rf" />
        <group name="lh" />
    </group>

    <end_effector name="lf_foot" parent_link="LF_FOOT" group="lf_leg" />
    <end_effector name="rf_foot" parent_link="RF_FOOT" group="rf_leg" />
    <end_effector name="lh_foot" parent_link="LH_FOOT" group="lh_leg" />
    <end_effector name="rh_foot" parent_link="RH_FOOT" group="rh_leg" />

    <group_state name="half_sitting" group="all_legs">
        <joint name="root_joint" value="0. 0. 0.4792 0. 0. 0. 1." />
        <joint name="LF_HAA" value="-0.1" />
        <joint name="LF_HFE" value="0.7" />
        <joint name="LF_KFE" value="-1." />
        <joint name="RF_HAA" value="0.1" />
        <joint name="RF_HFE" value="0.7" />
        <joint name="RF_KFE" value="-1." />
        <joint name="LH_HAA" value="-0.1" />
        <joint name="LH_HFE" value="-0.7" />
        <joint name="LH_KFE" value="1." />
        <joint name="RH_HAA" value="0.1" />
        <joint name="RH_HFE" value="-0.7" />
        <joint name="RH_KFE" value="1." />
    </group_state>

    <disable_collisions link1="LF_HIP" link2="LF_THIGH" reason="Adjacent" />
    <disable_collisions link1="LF_HIP" link2="LF_SHANK" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="LF_FOOT" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="RF_HIP" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="RF_THIGH" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="RF_SHANK" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="RF_FOOT" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="LH_HIP" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="LH_THIGH" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="LH_SHANK" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="LH_FOOT" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="RH_HIP" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="RH_THIGH" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="RH_SHANK" reason="Never" />
    <disable_collisions link1="LF_HIP" link2="RH_FOOT" reason="Never" />
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
    
    <disable_collisions link1="base" link2="LF_HIP" reason="Adjacent" />
    <disable_collisions link1="base" link2="LH_HIP" reason="Adjacent" />
    <disable_collisions link1="base" link2="RF_HIP" reason="Adjacent" />
    <disable_collisions link1="base" link2="RH_HIP" reason="Adjacent" />
    <disable_collisions link1="LF_HIP" link2="LF_THIGH" reason="Adjacent" />
    <disable_collisions link1="LH_HIP" link2="LH_THIGH" reason="Adjacent" />
    <disable_collisions link1="RF_HIP" link2="RF_THIGH" reason="Adjacent" />
    <disable_collisions link1="RH_HIP" link2="RH_THIGH" reason="Adjacent" />
    <disable_collisions link1="LF_THIGH" link2="LF_SHANK" reason="Adjacent" />
    <disable_collisions link1="LH_THIGH" link2="LH_SHANK" reason="Adjacent" />
    <disable_collisions link1="RF_THIGH" link2="RF_SHANK" reason="Adjacent" />
    <disable_collisions link1="RH_THIGH" link2="RH_SHANK" reason="Adjacent" />
    <disable_collisions link1="LF_SHANK" link2="LF_FOOT" reason="Adjacent" />
    <disable_collisions link1="LH_SHANK" link2="LH_FOOT" reason="Adjacent" />
    <disable_collisions link1="RF_SHANK" link2="RF_FOOT" reason="Adjacent" />
    <disable_collisions link1="RH_SHANK" link2="RH_FOOT" reason="Adjacent" />

    <disable_collisions link1="LF_ADAPTER" link2="LF_FOOT" reason="Adjacent" />
    <disable_collisions link1="LH_ADAPTER" link2="LH_FOOT" reason="Adjacent" />
    <disable_collisions link1="RF_ADAPTER" link2="RF_FOOT" reason="Adjacent" />
    <disable_collisions link1="RH_ADAPTER" link2="RH_FOOT" reason="Adjacent" />

    <disable_collisions link1="LF_ADAPTER" link2="LF_SHANK" reason="Adjacent" />
    <disable_collisions link1="LH_ADAPTER" link2="LH_SHANK" reason="Adjacent" />
    <disable_collisions link1="RF_ADAPTER" link2="RF_SHANK" reason="Adjacent" />
    <disable_collisions link1="RH_ADAPTER" link2="RH_SHANK" reason="Adjacent" />

    <disable_collisions link1="base" link2="imu_link" reason="Adjacent" />
    
    <!-- Need to check these 4 ? there may be auto-collisions ...  -->
    <disable_collisions link1="base" link2="LF_THIGH" reason="Adjacent" />
    <disable_collisions link1="base" link2="LH_THIGH" reason="Adjacent" />
    <disable_collisions link1="base" link2="RF_THIGH" reason="Adjacent" />
    <disable_collisions link1="base" link2="RH_THIGH" reason="Adjacent" />


132
133

</robot>