-
Notifications
You must be signed in to change notification settings - Fork 2
/
laikago.xml
133 lines (128 loc) · 10.4 KB
/
laikago.xml
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
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
132
133
<!-- =================================================
Copyright 2021 Vikash Kumar
Model :: unitree_a1 (MuJoCoV2.0)
Author :: Vikash Kumar (vikashplus@gmail.com)
Details :: https://github.com/vikashplus/unitree_sim
Credit :: Parameter details from https://github.com/unitreerobotics/unitree_pybullet
License :: Under Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
====================================================== -©vk©-->
<mujoco model="unitree_laikago">
<compiler angle="radian" />
<size njmax="500" nconmax="100" />
<asset>
<mesh name="trunk" file="../unitree_sim/meshes/laikago/trunk.stl" />
<mesh name="hip" file="../unitree_sim/meshes/laikago/hip.stl" />
<mesh name="thigh_mirror" file="../unitree_sim/meshes/laikago/thigh_mirror.stl" />
<mesh name="calf" file="../unitree_sim/meshes/laikago/calf.stl" />
<mesh name="thigh" file="../unitree_sim/meshes/laikago/thigh.stl" />
<material name="metal_grey" specular=".8" shininess=".8"/>
</asset>
<default>
<default class="laikago">
<joint limited="true" damping="10" armature="0.001" frictionloss=".2"/>
<geom contype="1" conaffinity="0" condim="4" margin="0.001" solref=".02 1" solimp=".8 .9 .01" group="4" rgba=".4 .5 .6 1"/>
<position ctrllimited="true"/>
<default class="viz_metal_grey">
<geom contype="0" conaffinity="0" type="mesh" material="metal_grey" rgba=".2 .2 .25 1" mass="0" group="1"/>
</default>
</default>
</default>
<include file="../unitree_sim/basic_scene.xml"/>
<worldbody>
<body name="laikago_torso" pos="0 0 0.52" childclass="laikago">
<geom class="viz_metal_grey" mesh="trunk" />
<geom size="0.2808 0.086 0.09375" pos="0 0 0.01675" type="box"/>
<freejoint/>
<body name="FR_hip" pos="0.21935 -0.0875 0">
<inertial pos="-0.001568 0.008134 0.000864" quat="0.629953 0.350191 0.35823 0.593462" mass="1.096" diaginertia="0.000983491 0.000885646 0.000800926" />
<joint name="FR_hip" pos="0 0 0" axis="1 0 0" limited="true" range="-1.0472 0.872665" />
<geom quat="0 1 0 0" class="viz_metal_grey"mesh="hip" />
<geom size="0.041 0.04" pos="0 0.021 0" quat="0.707107 0.707107 0 0" type="cylinder"/>
<body name="FR_thigh" pos="0 -0.037 0">
<inertial pos="-0.000482 -0.02001 -0.031996" quat="0.999848 0.00577968 -0.0153453 -0.00595156" mass="1.528" diaginertia="0.00992391 0.00928096 0.00177389" />
<joint name="FR_thigh" pos="0 0 0" axis="0 1 0" limited="true" range="-0.523599 3.92699" />
<geom class="viz_metal_grey"mesh="thigh_mirror" />
<geom size="0.125 0.017 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box"/>
<body name="FR_calf" pos="0 0 -0.25">
<inertial pos="-0.002196 -0.000381 -0.12338" quat="0.712765 0.000467477 -0.000119366 0.701402" mass="0.241" diaginertia="0.00619655 0.00618196 3.47683e-05" />
<joint name="FR_calf" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.610865" />
<geom class="viz_metal_grey" rgba="0.913725 0.913725 0.847059 1" mesh="calf" />
<geom size="0.125 0.008 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box"/>
<geom size="0.0275" pos="0 0 -0.25" type="sphere"/>
</body>
</body>
</body>
<body name="FL_hip" pos="0.21935 0.0875 0">
<inertial pos="-0.001568 -0.008134 0.000864" quat="0.593462 0.35823 0.350191 0.629953" mass="1.096" diaginertia="0.000983491 0.000885646 0.000800926" />
<joint name="FL_hip" pos="0 0 0" axis="1 0 0" limited="true" range="-0.872665 1.0472" />
<geom class="viz_metal_grey"mesh="hip" />
<geom size="0.041 0.04" pos="0 -0.021 0" quat="0.707107 0.707107 0 0" type="cylinder"/>
<body name="FL_thigh" pos="0 0.037 0">
<inertial pos="-0.000482 0.02001 -0.031996" quat="0.999848 -0.00577968 -0.0153453 0.00595156" mass="1.528" diaginertia="0.00992391 0.00928096 0.00177389" />
<joint name="FL_thigh" pos="0 0 0" axis="0 1 0" limited="true" range="-0.523599 3.92699" />
<geom class="viz_metal_grey"mesh="thigh" />
<geom size="0.125 0.017 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box"/>
<body name="FL_calf" pos="0 0 -0.25">
<inertial pos="-0.002196 -0.000381 -0.12338" quat="0.712765 0.000467477 -0.000119366 0.701402" mass="0.241" diaginertia="0.00619655 0.00618196 3.47683e-05" />
<joint name="FL_calf" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.610865" />
<geom class="viz_metal_grey" rgba="0.913725 0.913725 0.847059 1" mesh="calf" />
<geom size="0.125 0.008 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box"/>
<geom size="0.0275" pos="0 0 -0.25" type="sphere"/>
</body>
</body>
</body>
<body name="RR_hip" pos="-0.21935 -0.0875 0">
<inertial pos="0.001568 0.008134 0.000864" quat="0.35823 0.593462 0.629953 0.350191" mass="1.096" diaginertia="0.000983491 0.000885646 0.000800926" />
<joint name="RR_hip" pos="0 0 0" axis="1 0 0" limited="true" range="-1.0472 0.872665" />
<geom quat="0 0 0 -1" class="viz_metal_grey"mesh="hip" />
<geom size="0.041 0.04" pos="0 0.021 0" quat="0.707107 0.707107 0 0" type="cylinder"/>
<body name="RR_thigh" pos="0 -0.037 0">
<inertial pos="-0.000482 -0.02001 -0.031996" quat="0.999848 0.00577968 -0.0153453 -0.00595156" mass="1.528" diaginertia="0.00992391 0.00928096 0.00177389" />
<joint name="RR_thigh" pos="0 0 0" axis="0 1 0" limited="true" range="-0.523599 3.92699" />
<geom class="viz_metal_grey"mesh="thigh_mirror" />
<geom size="0.125 0.017 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box"/>
<body name="RR_calf" pos="0 0 -0.25">
<inertial pos="-0.002196 -0.000381 -0.12338" quat="0.712765 0.000467477 -0.000119366 0.701402" mass="0.241" diaginertia="0.00619655 0.00618196 3.47683e-05" />
<joint name="RR_calf" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.610865" />
<geom class="viz_metal_grey" rgba="0.913725 0.913725 0.847059 1" mesh="calf" />
<geom size="0.125 0.008 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box"/>
<geom size="0.0275" pos="0 0 -0.25" type="sphere"/>
</body>
</body>
</body>
<body name="RL_hip" pos="-0.21935 0.0875 0">
<inertial pos="0.001568 -0.008134 0.000864" quat="0.350191 0.629953 0.593462 0.35823" mass="1.096" diaginertia="0.000983491 0.000885646 0.000800926" />
<joint name="RL_hip" pos="0 0 0" axis="1 0 0" limited="true" range="-0.872665 1.0472" />
<geom quat="0 0 1 0" class="viz_metal_grey"mesh="hip" />
<geom size="0.041 0.04" pos="0 -0.021 0" quat="0.707107 0.707107 0 0" type="cylinder"/>
<body name="RL_thigh" pos="0 0.037 0">
<inertial pos="-0.000482 0.02001 -0.031996" quat="0.999848 -0.00577968 -0.0153453 0.00595156" mass="1.528" diaginertia="0.00992391 0.00928096 0.00177389" />
<joint name="RL_thigh" pos="0 0 0" axis="0 1 0" limited="true" range="-0.523599 3.92699" />
<geom class="viz_metal_grey"mesh="thigh" />
<geom size="0.125 0.017 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box"/>
<body name="RL_calf" pos="0 0 -0.25">
<inertial pos="-0.002196 -0.000381 -0.12338" quat="0.712765 0.000467477 -0.000119366 0.701402" mass="0.241" diaginertia="0.00619655 0.00618196 3.47683e-05" />
<joint name="RL_calf" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.610865" />
<geom class="viz_metal_grey" rgba="0.913725 0.913725 0.847059 1" mesh="calf" />
<geom size="0.125 0.008 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box"/>
<geom size="0.0275" pos="0 0 -0.25" type="sphere"/>
</body>
</body>
</body>
</body>
</worldbody>
<actuator>
<position name="FR_hip" kp="60" joint="FR_hip" class="laikago" ctrlrange="-0.802851 0.802851"/>
<position name="FR_thigh" kp="60" joint="FR_thigh" class="laikago" ctrlrange="-1.0472 4.18879"/>
<position name="FR_calf" kp="93.3" joint="FR_calf" class="laikago" ctrlrange="-2.69653 -0.916298"/>
<position name="FL_hip" kp="60" joint="FL_hip" class="laikago" ctrlrange="-0.802851 0.802851"/>
<position name="FL_thigh" kp="60" joint="FL_thigh" class="laikago" ctrlrange="-1.0472 4.18879"/>
<position name="FL_calf" kp="93.3" joint="FL_calf" class="laikago" ctrlrange="-2.69653 -0.916298"/>
<position name="RR_hip" kp="60" joint="RR_hip" class="laikago" ctrlrange="-0.802851 0.802851"/>
<position name="RR_thigh" kp="60" joint="RR_thigh" class="laikago" ctrlrange="-1.0472 4.18879"/>
<position name="RR_calf" kp="93.3" joint="RR_calf" class="laikago" ctrlrange="-2.69653 -0.916298"/>
<position name="RL_hip" kp="60" joint="RL_hip" class="laikago" ctrlrange="-0.802851 0.802851"/>
<position name="RL_thigh" kp="60" joint="RL_thigh" class="laikago" ctrlrange="-1.0472 4.18879"/>
<position name="RL_calf" kp="93.3" joint="RL_calf" class="laikago" ctrlrange="-2.69653 -0.916298"/>
</actuator>
</mujoco>