edit xml and python script
This commit is contained in:
parent
17814158fe
commit
62f3f933c2
|
@ -0,0 +1,122 @@
|
|||
<mujoco model="Robot_arm">
|
||||
<compiler angle="radian" meshdir='arm_meshes' balanceinertia='false'/>
|
||||
<size njmax="500" nconmax="100" />
|
||||
<option gravity='0 0 -9.806' iterations='50' solver='Newton' timestep='0.002'/>
|
||||
|
||||
<default>
|
||||
<geom contype="1" conaffinity="1" friction="0.6 0.3 0.3" rgba="0.5 0.6 0.7 1" margin="0.001" group="0"/>
|
||||
|
||||
<default class="visual">
|
||||
<geom contype="0" conaffinity="0" group="1" type="mesh" rgba="0.9 0.9 0.9 1.0"/>
|
||||
</default>
|
||||
|
||||
<light castshadow="false" diffuse="1 1 1"/>
|
||||
<motor ctrllimited='true'/>
|
||||
<camera fovy="60"/>
|
||||
<joint damping="0.01" armature="0.01"/>
|
||||
</default>
|
||||
|
||||
<asset>
|
||||
<mesh name="base_link" file="base_link.STL" />
|
||||
<mesh name="link_1" file="link_1.STL" />
|
||||
<mesh name="link_2" file="link_2.STL" />
|
||||
<mesh name="link_3" file="link_3.STL" />
|
||||
<mesh name="link_4" file="link_4.STL" />
|
||||
</asset>
|
||||
|
||||
<asset>
|
||||
<texture type="skybox" builtin="gradient" rgb1="1.0 1.0 1.0" rgb2="1.0 1.0 1.0" width="512" height="512"/>
|
||||
<texture name="plane" type="2d" builtin="flat" rgb1="1 1 1" rgb2="1 1 1" width="512" height="512" mark="cross" markrgb="0 0 0"/>
|
||||
<material name="plane" reflectance="0.0" texture="plane" texrepeat="3 3" texuniform="true"/>
|
||||
</asset>
|
||||
|
||||
<visual>
|
||||
<rgba com="0.502 1.0 0 0.5" contactforce="0.2 0.98 0.2 0.8" contactpoint="1.0 1.0 0.6 0.4"/>
|
||||
<scale com="0.2" forcewidth="0.05" contactwidth="0.10" contactheight="0.04"/>
|
||||
</visual>
|
||||
|
||||
<worldbody>
|
||||
<light directional="true" diffuse=".8 .8 .8" pos="0 0 10" dir="0 0 -10"/>
|
||||
<camera name="track" mode="trackcom" pos="0 -1.3 1.6" xyaxes="1 0 0 0 0.707 0.707"/>
|
||||
<geom name='floor' type='plane' conaffinity='1' condim='3' contype='1' rgba='1 1 1 1' material='plane' pos='0 0 0' size='0 0 1'/>
|
||||
|
||||
<body name='base_link' pos='0 0 1' euler='0 0 0'>
|
||||
|
||||
<!-- <joint type='free' limited='false' frictionloss='disable' damping='0' stiffness='0' armature='0' /> -->
|
||||
<geom type='mesh' mesh='base_link' class='visual'/>
|
||||
<geom name='base_link_collision' type='box' size='0.035 0.035 0.01' pos='0 0 0' euler='0 0 0' />
|
||||
<inertial pos='1.688E-07 -8.3907E-05 0.011068' mass='0.10458' fullinertia='7.0188E-05 4.9884E-05 7.6398E-05 1.1028E-09 2.5713E-11 3.4141E-07'/>
|
||||
<site name="imu" pos="0 0 0"/>
|
||||
|
||||
<!-- link1-->
|
||||
<body name="link_1" pos="0 -0.0001 0.049" quat="0.696006 0.696009 0.124794 -0.124794">
|
||||
<inertial pos="0.023572 0.014375 -0.00025895" quat="-0.0544401 0.710149 0.0551732 0.699771" mass="0.32357" diaginertia="0.00030638 0.000232161 0.000180019" />
|
||||
<joint name="joint_1" type='hinge' pos="0 0 0" axis="0 0 1" limited="true" range="-0.5 2" frictionloss='0.0'/>
|
||||
<geom type='mesh' rgba="1 1 1 1" mesh='link_1' class='visual'/>
|
||||
<geom name='link1_collision' type='box' size='0.04 0.032 0.02' pos='0.02 0.02 0' euler='0 0 0' />
|
||||
|
||||
<body name="link_2" pos="0.06855 0 0" quat="0.499998 -0.5 0.500002 -0.5">
|
||||
<inertial pos="-1.2238e-07 0.00020627 0.067735" quat="0.999997 0.0011959 -4.45307e-06 0.001984" mass="0.1626" diaginertia="0.000412886 0.000392583 7.94664e-05" />
|
||||
<joint name="joint_2" type='hinge' pos="0 0 0" axis="0 0 -1" limited="true" range="-3.14 3.14" frictionloss='0.0' />
|
||||
<geom type='mesh' mesh='link_2' class='visual'/>
|
||||
<geom name='link2_collision' type='cylinder' size='0.02 0.055' pos='0 0 0.06' euler='0 0 0' />
|
||||
|
||||
<body name="link_3" pos="0 0.00025 0.1414" quat="0.691267 0.69127 0.148821 -0.148821">
|
||||
<inertial pos="0.023572 0.014377 -0.00025896" quat="-0.0544841 0.710145 0.0552199 0.699769" mass="0.32357" diaginertia="0.000306351 0.000232164 0.000179987" />
|
||||
<joint name="joint_3" type='hinge' pos="0 0 0" axis="0 0 1" limited="true" range="-2 2" frictionloss='0.0' />
|
||||
<geom type='mesh' mesh='link_3' class='visual'/>
|
||||
<geom name='link3_collision' type='box' size='0.04 0.032 0.02' pos='0.02 0.02 0' euler='0 0 0'/>
|
||||
|
||||
<body name="link_4" pos="0.06855 0 0" quat="0.707105 0 0.707108 0">
|
||||
<inertial pos="-1.5087e-07 -1.6077e-07 0.067748" quat="0.923879 -9.48044e-07 -2.06085e-06 0.382685" mass="0.11973" diaginertia="0.000523594 0.000522057 4.41449e-05" />
|
||||
<joint name="joint_4" type='hinge' pos="0 0 0" axis="0 0 -1" limited="true" range="-3.14 3.14" frictionloss='0.0' />
|
||||
<geom type='mesh' mesh='link_4' class='visual'/>
|
||||
<geom name='link4_collision' type='cylinder' size='0.02 0.08' pos='0 0 0.08' euler='0 0 0'/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
|
||||
<!-- estiamted position -->
|
||||
<body name='estiamted_base_p' pos='0 0 0' mocap='true'>
|
||||
<geom name='base_position' conaffinity='0' contype='0' size='0.015' type='sphere' rgba='0 1 0 0.7' />
|
||||
</body>
|
||||
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
|
||||
<!-- <motor name='joint1_motor' joint='joint_1' gear='1' ctrllimited='true' ctrlrange='-60 60'/>
|
||||
<motor name='joint2_motor' joint='joint_2' gear='1' ctrllimited='true' ctrlrange='-60 60'/>
|
||||
<motor name='joint3_motor' joint='joint_3' gear='1' ctrllimited='true' ctrlrange='-60 60'/>
|
||||
<motor name='joint4_motor' joint='joint_4' gear='1' ctrllimited='true' ctrlrange='-60 60'/> -->
|
||||
|
||||
<position name='joint1_pos' joint='joint_1' gear='1' kp='150' ctrllimited='false' />
|
||||
<position name='joint2_pos' joint='joint_2' gear='1' kp='10' ctrllimited='false' />
|
||||
<position name='joint3_pos' joint='joint_3' gear='1' kp='10' ctrllimited='false' />
|
||||
<position name='joint4_pos' joint='joint_4' gear='1' kp='10' ctrllimited='false' />
|
||||
|
||||
<velocity name='joint1_vel' joint='joint_1' gear='1' kv='1' ctrllimited='false' />
|
||||
<velocity name='joint2_vel' joint='joint_2' gear='1' kv='1' ctrllimited='false' />
|
||||
<velocity name='joint3_vel' joint='joint_3' gear='1' kv='1' ctrllimited='false' />
|
||||
<velocity name='joint4_vel' joint='joint_4' gear='1' kv='1' ctrllimited='false' />
|
||||
</actuator>
|
||||
|
||||
<sensor>
|
||||
|
||||
<!-- sensordata index from 0-3 -->
|
||||
<jointpos name='Link1' joint='joint_1'/>
|
||||
<jointpos name='Link2' joint='joint_2'/>
|
||||
<jointpos name='Link3' joint='joint_3'/>
|
||||
<jointpos name='Link4' joint='joint_4'/>
|
||||
|
||||
<!-- sensordata index from 12-17 -->
|
||||
<jointvel name='Link1_vel' joint='joint_1'/>
|
||||
<jointvel name='Link2_vel' joint='joint_2'/>
|
||||
<jointvel name='Link3_vel' joint='joint_3'/>
|
||||
<jointvel name='Link4_vel' joint='joint_4'/>
|
||||
|
||||
</sensor>
|
||||
|
||||
</mujoco>
|
|
@ -10,7 +10,6 @@
|
|||
meshdir="../meshes/"
|
||||
balanceinertia="true"
|
||||
discardvisual="false" />
|
||||
<option gravity='0 0 -9.8'/>
|
||||
</mujoco>
|
||||
|
||||
<material name="black">
|
||||
|
|
|
@ -1,7 +1,19 @@
|
|||
<mujoco model="a1_description">
|
||||
<compiler angle="radian" meshdir="../meshes/" />
|
||||
<option gravity="0 0 -9.8" />
|
||||
<size njmax="500" nconmax="100" />
|
||||
|
||||
<option gravity='0 0 -9.806' iterations='50' solver='Newton' timestep='0.002'/>
|
||||
|
||||
<default>
|
||||
<geom contype="1" conaffinity="1" friction="0.6 0.3 0.3" rgba="0.5 0.6 0.7 1" margin="0.001" group="0"/>
|
||||
|
||||
<light castshadow="false" diffuse="1 1 1"/>
|
||||
<motor ctrlrange="-33.5 33.5" ctrllimited="true"/>
|
||||
<camera fovy="60"/>
|
||||
<joint damping="0.01" armature="0.01"/>
|
||||
|
||||
</default>
|
||||
|
||||
<asset>
|
||||
<mesh name="trunk" file="trunk.stl" />
|
||||
<mesh name="hip" file="hip.stl" />
|
||||
|
@ -9,11 +21,19 @@
|
|||
<mesh name="calf" file="calf.stl" />
|
||||
<mesh name="thigh" file="thigh.stl" />
|
||||
</asset>
|
||||
|
||||
<asset>
|
||||
<texture type="skybox" builtin="gradient" rgb1="1.0 1.0 1.0" rgb2="1.0 1.0 1.0" width="512" height="512"/>
|
||||
<texture name="plane" type="2d" builtin="flat" rgb1="1 1 1" rgb2="1 1 1" width="512" height="512" mark="cross" markrgb="0 0 0"/>
|
||||
<material name="plane" reflectance="0.0" texture="plane" texrepeat="3 3" texuniform="true"/>
|
||||
</asset>
|
||||
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom type="plane" pos="0 0 -0.45" size="10 10 0.1" rgba=".9 0 0 1"/>
|
||||
|
||||
<body name="trunk" pos="0 0 0">
|
||||
<light directional="true" diffuse=".8 .8 .8" pos="0 0 10" dir="0 0 -10"/>
|
||||
<camera name="track" mode="trackcom" pos="0 -1.3 1.6" xyaxes="1 0 0 0 0.707 0.707"/>
|
||||
<geom name='floor' type='plane' conaffinity='1' condim='3' contype='1' rgba="0.5 0.9 0.9 0.1" material='plane' pos='0 0 0' size='0 0 1'/>
|
||||
|
||||
<body name="trunk" pos="0 0 0.5">
|
||||
<inertial pos="0.0127283 0.00218554 0.000514891" quat="0.00186575 0.711506 0.000389649 0.702677" mass="4.714" diaginertia="0.0648213 0.0565803 0.0169323" />
|
||||
<joint name="floating_base" type="free" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="trunk" />
|
||||
|
@ -102,38 +122,50 @@
|
|||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
<!--
|
||||
<position joint="FR_hip_joint" kp="1000"/>
|
||||
<position joint="FR_thigh_joint" kp="1000"/>
|
||||
<position joint="FR_calf_joint" kp="1000"/>
|
||||
|
||||
<position joint="FL_hip_joint" kp="1000"/>
|
||||
<position joint="FL_thigh_joint" kp="1000"/>
|
||||
<position joint="FL_calf_joint" kp="1000"/>
|
||||
|
||||
<position joint="RR_hip_joint" kp="1000"/>
|
||||
<position joint="RR_thigh_joint" kp="1000"/>
|
||||
<position joint="RR_calf_joint" kp="1000"/>
|
||||
|
||||
<position joint="RL_hip_joint" kp="1000"/>
|
||||
<position joint="RL_thigh_joint" kp="1000"/>
|
||||
<position joint="RL_calf_joint" kp="1000"/> -->
|
||||
<actuator>
|
||||
|
||||
|
||||
<motor name="FR_hip" gear="9.1" joint="FR_hip_joint" forcerange="-33.5 33.5" />
|
||||
<motor name="FR_thigh" gear="9.1" joint="FR_thigh_joint" forcerange="-33.5 33.5" />
|
||||
<motor name="FR_calf" gear="9.1" joint="FR_calf_joint" forcerange="-33.5 33.5" />
|
||||
<motor name="FL_hip" gear="9.1" joint="FL_hip_joint" forcerange="-33.5 33.5" />
|
||||
<motor name="FL_thigh" gear="9.1" joint="FL_thigh_joint" forcerange="-33.5 33.5" />
|
||||
<motor name="FL_calf" gear="9.1" joint="FL_calf_joint" forcerange="-33.5 33.5" />
|
||||
<motor name="RR_hip" gear="9.1" joint="RR_hip_joint" forcerange="-33.5 33.5" />
|
||||
<motor name="RR_thigh" gear="9.1" joint="RR_thigh_joint" forcerange="-33.5 33.5" />
|
||||
<motor name="RR_calf" gear="9.1" joint="RR_calf_joint" forcerange="-33.5 33.5" />
|
||||
<motor name="RL_hip" gear="9.1" joint="RL_hip_joint" forcerange="-33.5 33.5" />
|
||||
<motor name="RL_thigh" gear="9.1" joint="RL_thigh_joint" forcerange="-33.5 33.5" />
|
||||
<motor name="RL_calf" gear="9.1" joint="RL_calf_joint" forcerange="-33.5 33.5" />
|
||||
<motor name="FR_hip" gear="1" joint="FR_hip_joint"/>
|
||||
<motor name="FR_thigh" gear="1" joint="FR_thigh_joint"/>
|
||||
<motor name="FR_calf" gear="1" joint="FR_calf_joint"/>
|
||||
<motor name="FL_hip" gear="1" joint="FL_hip_joint"/>
|
||||
<motor name="FL_thigh" gear="1" joint="FL_thigh_joint"/>
|
||||
<motor name="FL_calf" gear="1" joint="FL_calf_joint"/>
|
||||
<motor name="RR_hip" gear="1" joint="RR_hip_joint"/>
|
||||
<motor name="RR_thigh" gear="1" joint="RR_thigh_joint"/>
|
||||
<motor name="RR_calf" gear="1" joint="RR_calf_joint" />
|
||||
<motor name="RL_hip" gear="1" joint="RL_hip_joint"/>
|
||||
<motor name="RL_thigh" gear="1" joint="RL_thigh_joint"/>
|
||||
<motor name="RL_calf" gear="1" joint="RL_calf_joint"/>
|
||||
</actuator>
|
||||
|
||||
|
||||
<sensor>
|
||||
|
||||
<jointpos name="FR_hip_pos" joint="FR_hip_joint"/>
|
||||
<jointpos name="FR_thigh_pos" joint="FR_thigh_joint"/>
|
||||
<jointpos name="FR_calf_pos" joint="FR_calf_joint"/>
|
||||
<jointpos name="FL_hip_pos" joint="FL_hip_joint"/>
|
||||
<jointpos name="FL_thigh_pos" joint="FL_thigh_joint"/>
|
||||
<jointpos name="FL_calf_pos" joint="FL_calf_joint"/>
|
||||
<jointpos name="RR_hip_pos" joint="RR_hip_joint"/>
|
||||
<jointpos name="RR_thigh_pos" joint="RR_thigh_joint"/>
|
||||
<jointpos name="RR_calf_pos" joint="RR_calf_joint" />
|
||||
<jointpos name="RL_hip_pos" joint="RL_hip_joint"/>
|
||||
<jointpos name="RL_thigh_pos" joint="RL_thigh_joint"/>
|
||||
<jointpos name="RL_calf_pos" joint="RL_calf_joint"/>
|
||||
|
||||
<jointvel name="FR_hip_vel" joint="FR_hip_joint"/>
|
||||
<jointvel name="FR_thigh_vel" joint="FR_thigh_joint"/>
|
||||
<jointvel name="FR_calf_vel" joint="FR_calf_joint"/>
|
||||
<jointvel name="FL_hip_vel" joint="FL_hip_joint"/>
|
||||
<jointvel name="FL_thigh_vel" joint="FL_thigh_joint"/>
|
||||
<jointvel name="FL_calf_vel" joint="FL_calf_joint"/>
|
||||
<jointvel name="RR_hip_vel" joint="RR_hip_joint"/>
|
||||
<jointvel name="RR_thigh_vel" joint="RR_thigh_joint"/>
|
||||
<jointvel name="RR_calf_vel" joint="RR_calf_joint" />
|
||||
<jointvel name="RL_hip_vel" joint="RL_hip_joint"/>
|
||||
<jointvel name="RL_thigh_vel" joint="RL_thigh_joint"/>
|
||||
<jointvel name="RL_calf_vel" joint="RL_calf_joint"/>
|
||||
|
||||
</sensor>
|
||||
|
||||
</mujoco>
|
||||
|
|
|
@ -4,6 +4,13 @@
|
|||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="aliengo_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<mujoco>
|
||||
<compiler
|
||||
meshdir="../meshes/"
|
||||
balanceinertia="true"
|
||||
discardvisual="false" />
|
||||
</mujoco>
|
||||
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
@ -41,17 +48,10 @@
|
|||
<child link="base"/>
|
||||
</joint>
|
||||
</xacro:if> -->
|
||||
<link name="base">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="floating_base" type="fixed">
|
||||
<link name="world"/>
|
||||
<joint name="floating_base" type="floating">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="base"/>
|
||||
<parent link="world"/>
|
||||
<child link="trunk"/>
|
||||
</joint>
|
||||
<link name="trunk">
|
||||
|
@ -60,7 +60,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/trunk.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
|
@ -119,7 +119,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 -0.083 0"/>
|
||||
|
@ -161,7 +161,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/thigh_mirror.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
|
@ -189,7 +189,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
|
@ -214,7 +214,7 @@
|
|||
<geometry>
|
||||
<sphere radius="0.0165"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
|
@ -271,7 +271,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0.083 0"/>
|
||||
|
@ -313,7 +313,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/thigh.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
|
@ -341,7 +341,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
|
@ -366,7 +366,7 @@
|
|||
<geometry>
|
||||
<sphere radius="0.0165"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
|
@ -423,7 +423,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 -0.083 0"/>
|
||||
|
@ -465,7 +465,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/thigh_mirror.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
|
@ -493,7 +493,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
|
@ -518,7 +518,7 @@
|
|||
<geometry>
|
||||
<sphere radius="0.0165"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
|
@ -575,7 +575,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0.083 0"/>
|
||||
|
@ -617,7 +617,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/thigh.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
|
@ -645,7 +645,7 @@
|
|||
<geometry>
|
||||
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
|
||||
|
@ -670,7 +670,7 @@
|
|||
<geometry>
|
||||
<sphere radius="0.0165"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
|
|
|
@ -0,0 +1,169 @@
|
|||
<mujoco model="aliengo_description">
|
||||
<compiler angle="radian" meshdir="../meshes/" />
|
||||
<size njmax="500" nconmax="100" />
|
||||
<option gravity='0 0 -9.806' iterations='50' solver='Newton' timestep='0.002'/>
|
||||
|
||||
<default>
|
||||
<geom contype="1" conaffinity="1" friction="0.6 0.3 0.3" rgba="0.5 0.6 0.7 1" margin="0.001" group="0"/>
|
||||
|
||||
<light castshadow="false" diffuse="1 1 1"/>
|
||||
<motor ctrlrange="-33.5 33.5" ctrllimited="true"/>
|
||||
<camera fovy="60"/>
|
||||
<joint damping="0.01" armature="0.01"/>
|
||||
|
||||
</default>
|
||||
|
||||
<asset>
|
||||
<mesh name="trunk" file="trunk.stl" />
|
||||
<mesh name="hip" file="hip.stl" />
|
||||
<mesh name="thigh_mirror" file="thigh_mirror.stl" />
|
||||
<mesh name="calf" file="calf.stl" />
|
||||
<mesh name="thigh" file="thigh.stl" />
|
||||
</asset>
|
||||
|
||||
<asset>
|
||||
<texture type="skybox" builtin="gradient" rgb1="1.0 1.0 1.0" rgb2="1.0 1.0 1.0" width="512" height="512"/>
|
||||
<texture name="plane" type="2d" builtin="flat" rgb1="1 1 1" rgb2="1 1 1" width="512" height="512" mark="cross" markrgb="0 0 0"/>
|
||||
<material name="plane" reflectance="0.0" texture="plane" texrepeat="3 3" texuniform="true"/>
|
||||
</asset>
|
||||
|
||||
<worldbody>
|
||||
<light directional="true" diffuse=".8 .8 .8" pos="0 0 10" dir="0 0 -10"/>
|
||||
<camera name="track" mode="trackcom" pos="0 -1.3 1.6" xyaxes="1 0 0 0 0.707 0.707"/>
|
||||
<geom name='floor' type='plane' conaffinity='1' condim='3' contype='1' rgba="0.5 0.9 0.9 0.1" material='plane' pos='0 0 0' size='0 0 1'/>
|
||||
|
||||
<body name="trunk" pos="0 0 0.5">
|
||||
<inertial pos="0.00846406 0.00404455 -0.000762916" quat="-3.12625e-05 0.708321 0.00247254 0.705886" mass="9.042" diaginertia="0.174706 0.161175 0.033357" />
|
||||
<joint name="floating_base" type="free" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="trunk" />
|
||||
<geom size="0.3235 0.075 0.056" type="box" rgba="0.2 0.2 0.2 0" />
|
||||
<geom size="0.0005 0.0005 0.0005" type="box" contype="0" conaffinity="0" group="1" rgba="0.8 0 0 0" />
|
||||
<geom size="0.0005 0.0005 0.0005" type="box" rgba="0.8 0 0 0" />
|
||||
<body name="FR_hip" pos="0.2399 -0.051 0">
|
||||
<inertial pos="-0.022191 -0.015144 -1.5e-05" quat="0.0135493 0.706835 -0.0117635 0.707151" mass="1.993" diaginertia="0.00558695 0.00491009 0.00290132" />
|
||||
<joint name="FR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-1.22173 1.22173" />
|
||||
<geom quat="0 1 0 0" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
|
||||
<geom size="0.046 0.0209" pos="0 -0.083 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.2 0.2 0.2 0" />
|
||||
<body name="FR_thigh" pos="0 -0.083 0">
|
||||
<inertial pos="-0.005607 0.003877 -0.048199" quat="0.694544 -0.0335669 -0.031246 0.717987" mass="0.639" diaginertia="0.0058474 0.00571186 0.000324584" />
|
||||
<joint name="FR_thigh_joint" pos="0 0 0" axis="0 1 0" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="thigh_mirror" />
|
||||
<geom size="0.125 0.0187 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.2 0.2 0.2 0" />
|
||||
<body name="FR_calf" pos="0 0 -0.25">
|
||||
<inertial pos="0.00215606 4.88427e-05 -0.166671" quat="0.707462 0.00517582 0.00535172 0.706712" mass="0.267" diaginertia="0.00690975 0.00689712 5.4885e-05" />
|
||||
<joint name="FR_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.645772" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
|
||||
<geom size="0.125 0.0104 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
|
||||
<geom size="0.0165" pos="0 0 -0.25" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
|
||||
<geom size="0.0265" pos="0 0 -0.25" rgba="0 0 0 1" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="FL_hip" pos="0.2399 0.051 0">
|
||||
<inertial pos="-0.022191 0.015144 -1.5e-05" quat="-0.0135493 0.706835 0.0117635 0.707151" mass="1.993" diaginertia="0.00558695 0.00491009 0.00290132" />
|
||||
<joint name="FL_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-1.22173 1.22173" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
|
||||
<geom size="0.046 0.0209" pos="0 0.083 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.2 0.2 0.2 0" />
|
||||
<body name="FL_thigh" pos="0 0.083 0">
|
||||
<inertial pos="-0.005607 -0.003877 -0.048199" quat="0.717987 -0.031246 -0.0335669 0.694544" mass="0.639" diaginertia="0.0058474 0.00571186 0.000324584" />
|
||||
<joint name="FL_thigh_joint" pos="0 0 0" axis="0 1 0" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="thigh" />
|
||||
<geom size="0.125 0.0187 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.2 0.2 0.2 0" />
|
||||
<body name="FL_calf" pos="0 0 -0.25">
|
||||
<inertial pos="0.00215606 4.88427e-05 -0.166671" quat="0.707462 0.00517582 0.00535172 0.706712" mass="0.267" diaginertia="0.00690975 0.00689712 5.4885e-05" />
|
||||
<joint name="FL_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.645772" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
|
||||
<geom size="0.125 0.0104 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
|
||||
<geom size="0.0165" pos="0 0 -0.25" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
|
||||
<geom size="0.0265" pos="0 0 -0.25" rgba="0 0 0 1" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="RR_hip" pos="-0.2399 -0.051 0">
|
||||
<inertial pos="0.022191 -0.015144 -1.5e-05" quat="-0.0117635 0.707151 0.0135493 0.706835" mass="1.993" diaginertia="0.00558695 0.00491009 0.00290132" />
|
||||
<joint name="RR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-1.22173 1.22173" />
|
||||
<geom quat="0 0 0 -1" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
|
||||
<geom size="0.046 0.0209" pos="0 -0.083 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.2 0.2 0.2 0" />
|
||||
<body name="RR_thigh" pos="0 -0.083 0">
|
||||
<inertial pos="-0.005607 0.003877 -0.048199" quat="0.694544 -0.0335669 -0.031246 0.717987" mass="0.639" diaginertia="0.0058474 0.00571186 0.000324584" />
|
||||
<joint name="RR_thigh_joint" pos="0 0 0" axis="0 1 0" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="thigh_mirror" />
|
||||
<geom size="0.125 0.0187 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.2 0.2 0.2 0" />
|
||||
<body name="RR_calf" pos="0 0 -0.25">
|
||||
<inertial pos="0.00215606 4.88427e-05 -0.166671" quat="0.707462 0.00517582 0.00535172 0.706712" mass="0.267" diaginertia="0.00690975 0.00689712 5.4885e-05" />
|
||||
<joint name="RR_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.645772" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
|
||||
<geom size="0.125 0.0104 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
|
||||
<geom size="0.0165" pos="0 0 -0.25" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
|
||||
<geom size="0.0265" pos="0 0 -0.25" rgba="0 0 0 1" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="RL_hip" pos="-0.2399 0.051 0">
|
||||
<inertial pos="0.022191 0.015144 -1.5e-05" quat="0.0117635 0.707151 -0.0135493 0.706835" mass="1.993" diaginertia="0.00558695 0.00491009 0.00290132" />
|
||||
<joint name="RL_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-1.22173 1.22173" />
|
||||
<geom quat="0 0 1 0" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
|
||||
<geom size="0.046 0.0209" pos="0 0.083 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.2 0.2 0.2 0" />
|
||||
<body name="RL_thigh" pos="0 0.083 0">
|
||||
<inertial pos="-0.005607 -0.003877 -0.048199" quat="0.717987 -0.031246 -0.0335669 0.694544" mass="0.639" diaginertia="0.0058474 0.00571186 0.000324584" />
|
||||
<joint name="RL_thigh_joint" pos="0 0 0" axis="0 1 0" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="thigh" />
|
||||
<geom size="0.125 0.0187 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.2 0.2 0.2 0" />
|
||||
<body name="RL_calf" pos="0 0 -0.25">
|
||||
<inertial pos="0.00215606 4.88427e-05 -0.166671" quat="0.707462 0.00517582 0.00535172 0.706712" mass="0.267" diaginertia="0.00690975 0.00689712 5.4885e-05" />
|
||||
<joint name="RL_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.645772" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
|
||||
<geom size="0.125 0.0104 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
|
||||
<geom size="0.0165" pos="0 0 -0.25" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
|
||||
<geom size="0.0265" pos="0 0 -0.25" rgba="0 0 0 1" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
|
||||
<motor name="FR_hip" gear="1" joint="FR_hip_joint"/>
|
||||
<motor name="FR_thigh" gear="1" joint="FR_thigh_joint"/>
|
||||
<motor name="FR_calf" gear="1" joint="FR_calf_joint"/>
|
||||
<motor name="FL_hip" gear="1" joint="FL_hip_joint"/>
|
||||
<motor name="FL_thigh" gear="1" joint="FL_thigh_joint"/>
|
||||
<motor name="FL_calf" gear="1" joint="FL_calf_joint"/>
|
||||
<motor name="RR_hip" gear="1" joint="RR_hip_joint"/>
|
||||
<motor name="RR_thigh" gear="1" joint="RR_thigh_joint"/>
|
||||
<motor name="RR_calf" gear="1" joint="RR_calf_joint" />
|
||||
<motor name="RL_hip" gear="1" joint="RL_hip_joint"/>
|
||||
<motor name="RL_thigh" gear="1" joint="RL_thigh_joint"/>
|
||||
<motor name="RL_calf" gear="1" joint="RL_calf_joint"/>
|
||||
</actuator>
|
||||
|
||||
<sensor>
|
||||
|
||||
<jointpos name="FR_hip_pos" joint="FR_hip_joint"/>
|
||||
<jointpos name="FR_thigh_pos" joint="FR_thigh_joint"/>
|
||||
<jointpos name="FR_calf_pos" joint="FR_calf_joint"/>
|
||||
<jointpos name="FL_hip_pos" joint="FL_hip_joint"/>
|
||||
<jointpos name="FL_thigh_pos" joint="FL_thigh_joint"/>
|
||||
<jointpos name="FL_calf_pos" joint="FL_calf_joint"/>
|
||||
<jointpos name="RR_hip_pos" joint="RR_hip_joint"/>
|
||||
<jointpos name="RR_thigh_pos" joint="RR_thigh_joint"/>
|
||||
<jointpos name="RR_calf_pos" joint="RR_calf_joint" />
|
||||
<jointpos name="RL_hip_pos" joint="RL_hip_joint"/>
|
||||
<jointpos name="RL_thigh_pos" joint="RL_thigh_joint"/>
|
||||
<jointpos name="RL_calf_pos" joint="RL_calf_joint"/>
|
||||
|
||||
<jointvel name="FR_hip_vel" joint="FR_hip_joint"/>
|
||||
<jointvel name="FR_thigh_vel" joint="FR_thigh_joint"/>
|
||||
<jointvel name="FR_calf_vel" joint="FR_calf_joint"/>
|
||||
<jointvel name="FL_hip_vel" joint="FL_hip_joint"/>
|
||||
<jointvel name="FL_thigh_vel" joint="FL_thigh_joint"/>
|
||||
<jointvel name="FL_calf_vel" joint="FL_calf_joint"/>
|
||||
<jointvel name="RR_hip_vel" joint="RR_hip_joint"/>
|
||||
<jointvel name="RR_thigh_vel" joint="RR_thigh_joint"/>
|
||||
<jointvel name="RR_calf_vel" joint="RR_calf_joint" />
|
||||
<jointvel name="RL_hip_vel" joint="RL_hip_joint"/>
|
||||
<jointvel name="RL_thigh_vel" joint="RL_thigh_joint"/>
|
||||
<jointvel name="RL_calf_vel" joint="RL_calf_joint"/>
|
||||
|
||||
</sensor>
|
||||
</mujoco>
|
|
@ -4,6 +4,14 @@
|
|||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="laikago_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<mujoco>
|
||||
<compiler
|
||||
meshdir="../meshes/"
|
||||
balanceinertia="true"
|
||||
discardvisual="false" />
|
||||
</mujoco>
|
||||
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
@ -32,13 +40,20 @@
|
|||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<link name="world"/>
|
||||
<joint name="floating_base" type="floating">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="trunk"/>
|
||||
</joint>
|
||||
|
||||
<link name="trunk">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/trunk.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="orange"/>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.01675"/>
|
||||
|
|
|
@ -0,0 +1,159 @@
|
|||
<mujoco model="laikago_description">
|
||||
<compiler angle="radian" meshdir="../meshes/" />
|
||||
<size njmax="500" nconmax="100" />
|
||||
<option gravity='0 0 -9.806' iterations='50' solver='Newton' timestep='0.002'/>
|
||||
|
||||
<default>
|
||||
<geom contype="1" conaffinity="1" friction="0.6 0.3 0.3" rgba="0.5 0.6 0.7 1" margin="0.001" group="0"/>
|
||||
|
||||
<light castshadow="false" diffuse="1 1 1"/>
|
||||
<motor ctrlrange="-33.5 33.5" ctrllimited="true"/>
|
||||
<camera fovy="60"/>
|
||||
<joint damping="0.01" armature="0.01"/>
|
||||
|
||||
</default>
|
||||
|
||||
<asset>
|
||||
<mesh name="trunk" file="trunk.stl" />
|
||||
<mesh name="hip" file="hip.stl" />
|
||||
<mesh name="thigh_mirror" file="thigh_mirror.stl" />
|
||||
<mesh name="calf" file="calf.stl" />
|
||||
<mesh name="thigh" file="thigh.stl" />
|
||||
</asset>
|
||||
|
||||
<asset>
|
||||
<texture type="skybox" builtin="gradient" rgb1="1.0 1.0 1.0" rgb2="1.0 1.0 1.0" width="512" height="512"/>
|
||||
<texture name="plane" type="2d" builtin="flat" rgb1="1 1 1" rgb2="1 1 1" width="512" height="512" mark="cross" markrgb="0 0 0"/>
|
||||
<material name="plane" reflectance="0.0" texture="plane" texrepeat="3 3" texuniform="true"/>
|
||||
</asset>
|
||||
<worldbody>
|
||||
<light directional="true" diffuse=".8 .8 .8" pos="0 0 10" dir="0 0 -10"/>
|
||||
<camera name="track" mode="trackcom" pos="0 -1.3 1.6" xyaxes="1 0 0 0 0.707 0.707"/>
|
||||
<geom name='floor' type='plane' conaffinity='1' condim='3' contype='1' rgba="0.5 0.9 0.9 0.1" material='plane' pos='0 0 0' size='0 0 1'/>
|
||||
|
||||
<body name="trunk" pos="0 0 0.55">
|
||||
<inertial pos="0.002284 -4.1e-05 0.025165" quat="-0.00605949 0.710803 -0.00734309 0.703327" mass="13.733" diaginertia="0.254491 0.250684 0.0733281" />
|
||||
<joint name="floating_base" type="free" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="trunk" />
|
||||
<geom size="0.2808 0.086 0.09375" pos="0 0 0.01675" type="box" rgba="0.2 0.2 0.2 0" />
|
||||
<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_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-1.0472 0.872665" />
|
||||
<geom quat="0 1 0 0" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
|
||||
<geom size="0.041 0.04" pos="0 0.021 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.2 0.2 0.2 0" />
|
||||
<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_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-0.523599 3.92699" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" 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" rgba="0.2 0.2 0.2 0" />
|
||||
<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_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.610865" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" 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" rgba="0.913725 0.913725 0.847059 0" />
|
||||
</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_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.872665 1.0472" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
|
||||
<geom size="0.041 0.04" pos="0 -0.021 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.2 0.2 0.2 0" />
|
||||
<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_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-0.523599 3.92699" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="thigh" />
|
||||
<geom size="0.125 0.017 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.2 0.2 0.2 0" />
|
||||
<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_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.610865" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" 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" rgba="0.913725 0.913725 0.847059 0" />
|
||||
</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_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-1.0472 0.872665" />
|
||||
<geom quat="0 0 0 -1" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
|
||||
<geom size="0.041 0.04" pos="0 0.021 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.2 0.2 0.2 0" />
|
||||
<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_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-0.523599 3.92699" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" 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" rgba="0.2 0.2 0.2 0" />
|
||||
<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_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.610865" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" 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" rgba="0.913725 0.913725 0.847059 0" />
|
||||
</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_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.872665 1.0472" />
|
||||
<geom quat="0 0 1 0" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
|
||||
<geom size="0.041 0.04" pos="0 -0.021 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.2 0.2 0.2 0" />
|
||||
<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_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-0.523599 3.92699" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="thigh" />
|
||||
<geom size="0.125 0.017 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.2 0.2 0.2 0" />
|
||||
<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_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.610865" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" 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" rgba="0.913725 0.913725 0.847059 0" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
|
||||
<motor name="FR_hip" gear="1" joint="FR_hip_joint"/>
|
||||
<motor name="FR_thigh" gear="1" joint="FR_thigh_joint"/>
|
||||
<motor name="FR_calf" gear="1" joint="FR_calf_joint"/>
|
||||
<motor name="FL_hip" gear="1" joint="FL_hip_joint"/>
|
||||
<motor name="FL_thigh" gear="1" joint="FL_thigh_joint"/>
|
||||
<motor name="FL_calf" gear="1" joint="FL_calf_joint"/>
|
||||
<motor name="RR_hip" gear="1" joint="RR_hip_joint"/>
|
||||
<motor name="RR_thigh" gear="1" joint="RR_thigh_joint"/>
|
||||
<motor name="RR_calf" gear="1" joint="RR_calf_joint" />
|
||||
<motor name="RL_hip" gear="1" joint="RL_hip_joint"/>
|
||||
<motor name="RL_thigh" gear="1" joint="RL_thigh_joint"/>
|
||||
<motor name="RL_calf" gear="1" joint="RL_calf_joint"/>
|
||||
</actuator>
|
||||
|
||||
<sensor>
|
||||
|
||||
<jointpos name="FR_hip_pos" joint="FR_hip_joint"/>
|
||||
<jointpos name="FR_thigh_pos" joint="FR_thigh_joint"/>
|
||||
<jointpos name="FR_calf_pos" joint="FR_calf_joint"/>
|
||||
<jointpos name="FL_hip_pos" joint="FL_hip_joint"/>
|
||||
<jointpos name="FL_thigh_pos" joint="FL_thigh_joint"/>
|
||||
<jointpos name="FL_calf_pos" joint="FL_calf_joint"/>
|
||||
<jointpos name="RR_hip_pos" joint="RR_hip_joint"/>
|
||||
<jointpos name="RR_thigh_pos" joint="RR_thigh_joint"/>
|
||||
<jointpos name="RR_calf_pos" joint="RR_calf_joint" />
|
||||
<jointpos name="RL_hip_pos" joint="RL_hip_joint"/>
|
||||
<jointpos name="RL_thigh_pos" joint="RL_thigh_joint"/>
|
||||
<jointpos name="RL_calf_pos" joint="RL_calf_joint"/>
|
||||
|
||||
<jointvel name="FR_hip_vel" joint="FR_hip_joint"/>
|
||||
<jointvel name="FR_thigh_vel" joint="FR_thigh_joint"/>
|
||||
<jointvel name="FR_calf_vel" joint="FR_calf_joint"/>
|
||||
<jointvel name="FL_hip_vel" joint="FL_hip_joint"/>
|
||||
<jointvel name="FL_thigh_vel" joint="FL_thigh_joint"/>
|
||||
<jointvel name="FL_calf_vel" joint="FL_calf_joint"/>
|
||||
<jointvel name="RR_hip_vel" joint="RR_hip_joint"/>
|
||||
<jointvel name="RR_thigh_vel" joint="RR_thigh_joint"/>
|
||||
<jointvel name="RR_calf_vel" joint="RR_calf_joint" />
|
||||
<jointvel name="RL_hip_vel" joint="RL_hip_joint"/>
|
||||
<jointvel name="RL_thigh_vel" joint="RL_thigh_joint"/>
|
||||
<jointvel name="RL_calf_vel" joint="RL_calf_joint"/>
|
||||
|
||||
</sensor>
|
||||
|
||||
</mujoco>
|
|
@ -8,80 +8,15 @@ import os
|
|||
import math
|
||||
import keyboard
|
||||
|
||||
model = load_model_from_path("/home/bobzhu/Unitree/Mujoco/unitree_mujoco_git/unitree_mujoco/data/a1/urdf/a1.xml")
|
||||
model = load_model_from_path("/path/to/a1.xml")
|
||||
sim = MjSim(model)
|
||||
|
||||
viewer = MjViewer(sim)
|
||||
|
||||
sim_state = sim.get_state()
|
||||
|
||||
i = 0
|
||||
if_increase = True
|
||||
|
||||
desired_speed = [0.0] * 12
|
||||
desired_pos = [0.0] * 12
|
||||
Kp_vel= 7.0
|
||||
Ki_vel = 0.8
|
||||
|
||||
Kp_pos= 10.0
|
||||
|
||||
q_vel_former = [0.0] * 12
|
||||
|
||||
speed_command = [0.0] * 12
|
||||
speed_error = [0.0] * 12
|
||||
speed_error_former = [0.0] * 12
|
||||
|
||||
angle_error = [0.0] * 12
|
||||
|
||||
|
||||
k = 0
|
||||
increase = True
|
||||
while True:
|
||||
|
||||
#sim.set_state(sim_state)
|
||||
|
||||
# if k > 50:
|
||||
# increase = False
|
||||
# elif k < -50:
|
||||
# increase = True
|
||||
|
||||
# if increase:
|
||||
# k+=1
|
||||
# else:
|
||||
# k-=1
|
||||
|
||||
# # print(desired_pos)
|
||||
# for i in range(12):
|
||||
# desired_pos[i] = 0.0
|
||||
|
||||
# q_pos_meas = sim.data.get_joint_qpos(sim.model.joint_names[i])
|
||||
|
||||
# angle_error[i] = desired_pos[i] - q_pos_meas
|
||||
|
||||
# if angle_error[i] < - math.pi:
|
||||
# angle_error[i] = 2 * math.pi + angle_error[i]
|
||||
# elif angle_error[i] >= math.pi:
|
||||
# angle_error[i] = angle_error[i] - 2 * math.pi
|
||||
|
||||
# desired_speed[i] = Kp_pos * angle_error[i]
|
||||
|
||||
# q_vel_meas = sim.data.get_joint_qvel(sim.model.joint_names[i])
|
||||
# #print(sim.data.get_joint_qvel(sim.model.joint_names[0]))
|
||||
|
||||
# speed_error[i] = desired_speed[i] - q_vel_meas
|
||||
# speed_command[i] += Kp_vel * (speed_error[i] - speed_error_former[i]) + Ki_vel * speed_error[i]
|
||||
# speed_error_former[i] = speed_error[i]
|
||||
|
||||
# if speed_command[i] > 33.5:
|
||||
# speed_command[i] = 33.5
|
||||
# elif speed_command[i] < -33.5:
|
||||
# speed_command[i] = -33.5
|
||||
|
||||
# sim.data.ctrl[i] = speed_command[i]
|
||||
|
||||
#sim.data.ctrl[:] = k / 10
|
||||
|
||||
#print(joint_name, sim.data.get_joint_qpos(joint_name), sim.data.get_joint_qvel(joint_name))
|
||||
sim.step()
|
||||
viewer.render()
|
||||
#print(" ")
|
||||
|
|
Loading…
Reference in New Issue