add go1
This commit is contained in:
parent
d12271b5a1
commit
d9a3e31d1a
|
@ -1,7 +1,6 @@
|
|||
<mujoco model="a1_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>
|
||||
|
@ -10,7 +9,7 @@
|
|||
<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"/>
|
||||
<joint damping="0.01" armature="0.01" frictionloss="0.2" />
|
||||
|
||||
</default>
|
||||
|
||||
|
@ -28,18 +27,25 @@
|
|||
<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.98 0.4 0.4 0.7" contactpoint="1.0 1.0 0.6 0.4"/>
|
||||
<scale com="0.2" forcewidth="0.035" 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="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">
|
||||
<body name="trunk" pos="0 0 0.3">
|
||||
<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 type="free" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="trunk" />
|
||||
<geom size="0.1335 0.097 0.057" type="box" rgba="0.913725 0.913725 0.847059 0" />
|
||||
<geom size="0.1335 0.066 0.057" type="box" rgba="0.913725 0.913725 0.847059 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" />
|
||||
<site name="imu" pos="0 0 0"/>
|
||||
|
||||
<body name="FR_hip" pos="0.183 -0.047 0">
|
||||
<inertial pos="-0.003311 -0.000635 3.1e-05" quat="0.507528 0.506268 0.491507 0.494499" mass="0.696" diaginertia="0.000807752 0.00055293 0.000468983" />
|
||||
<joint name="FR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
|
||||
|
@ -166,6 +172,15 @@
|
|||
<jointvel name="RL_thigh_vel" joint="RL_thigh_joint"/>
|
||||
<jointvel name="RL_calf_vel" joint="RL_calf_joint"/>
|
||||
|
||||
<accelerometer name="Body_Acc" site="imu"/>
|
||||
|
||||
<gyro name="Body_Gyro" site="imu"/>
|
||||
|
||||
<framepos name="Body_Pos" objtype=site objname="imu"/>
|
||||
|
||||
<framequat name="Body_Quat" objtype=site objname="imu"/>
|
||||
|
||||
|
||||
</sensor>
|
||||
|
||||
</mujoco>
|
|
@ -49,7 +49,7 @@
|
|||
</joint>
|
||||
</xacro:if> -->
|
||||
<link name="world"/>
|
||||
<joint name="" type="floating">
|
||||
<joint name="floating_base" type="floating">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="trunk"/>
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
<light castshadow="false" diffuse="1 1 1"/>
|
||||
<motor ctrlrange="-44.4 44.4" ctrllimited="true"/>
|
||||
<camera fovy="60"/>
|
||||
<joint damping="0.01" armature="0.01"/>
|
||||
<joint damping="0.01" armature="0.01" frictionloss="0.2" />
|
||||
|
||||
</default>
|
||||
|
||||
|
@ -27,18 +27,25 @@
|
|||
<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.98 0.4 0.4 0.7" contactpoint="1.0 1.0 0.6 0.4"/>
|
||||
<scale com="0.2" forcewidth="0.035" 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="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">
|
||||
<body name="trunk" pos="0 0 0.4">
|
||||
<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 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.18 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" />
|
||||
<site name="imu" pos="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" />
|
||||
|
@ -121,6 +128,7 @@
|
|||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
|
||||
<motor name="FR_hip" gear="1" joint="FR_hip_joint"/>
|
||||
|
@ -165,5 +173,13 @@
|
|||
<jointvel name="RL_thigh_vel" joint="RL_thigh_joint"/>
|
||||
<jointvel name="RL_calf_vel" joint="RL_calf_joint"/>
|
||||
|
||||
<accelerometer name="Body_Acc" site="imu"/>
|
||||
|
||||
<gyro name="Body_Gyro" site="imu"/>
|
||||
|
||||
<framepos name="Body_Pos" objtype=site objname="imu"/>
|
||||
|
||||
<framequat name="Body_Quat" objtype=site objname="imu"/>
|
||||
|
||||
</sensor>
|
||||
</mujoco>
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,704 @@
|
|||
<?xml version="1.0" ?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from robot.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="go1_description">
|
||||
|
||||
<mujoco>
|
||||
<compiler
|
||||
meshdir="../meshes/"
|
||||
balanceinertia="true"
|
||||
discardvisual="false" />
|
||||
</mujoco>
|
||||
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="blue">
|
||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||
</material>
|
||||
<material name="green">
|
||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
||||
</material>
|
||||
<material name="silver">
|
||||
<color rgba="0.913725490196 0.913725490196 0.847058823529 1.0"/>
|
||||
</material>
|
||||
<material name="orange">
|
||||
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
|
||||
</material>
|
||||
<material name="brown">
|
||||
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
|
||||
</material>
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
|
||||
<link name="world"/>
|
||||
<joint name="" 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="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.3762 0.0935 0.114"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.011611 0.004437 0.000108"/>
|
||||
<mass value="4.8"/>
|
||||
<inertia ixx="0.016130741919" ixy="0.000593180607" ixz="7.324662e-06" iyy="0.036507810812" iyz="2.0969537e-05" izz="0.044693872053"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="imu_link"/>
|
||||
<origin rpy="0 0 0" xyz="-0.01592 -0.06659 -0.00617"/>
|
||||
</joint>
|
||||
<link name="imu_link">
|
||||
<inertial>
|
||||
<mass value="0.001"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.1881 -0.04675 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-0.802851455917" upper="0.802851455917" velocity="21"/>
|
||||
</joint>
|
||||
<link name="FR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 -0.045 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.00541 0.00074 6e-06"/>
|
||||
<mass value="0.510299"/>
|
||||
<inertia ixx="0.00030528937" ixy="7.788013e-06" ixz="2.2016e-07" iyy="0.000590894859" iyz="1.7175e-08" izz="0.000396594572"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 -0.08 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="FR_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FR_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.08 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-1.0471975512" upper="4.18879020479" velocity="21"/>
|
||||
</joint>
|
||||
<link name="FR_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/thigh_mirror.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003468 0.018947 -0.032736"/>
|
||||
<mass value="0.898919"/>
|
||||
<inertia ixx="0.005395867678" ixy="-1.02809e-07" ixz="0.000337529085" iyy="0.005142451046" iyz="5.816563e-06" izz="0.00102478732"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="FR_thigh"/>
|
||||
<child link="FR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-2.69653369433" upper="-0.916297857297" velocity="21"/>
|
||||
</joint>
|
||||
<link name="FR_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006286 0.001307 -0.122269"/>
|
||||
<mass value="0.158015"/>
|
||||
<inertia ixx="0.003607648222" ixy="1.494971e-06" ixz="-0.000132778525" iyy="0.003626771492" iyz="-2.8638535e-05" izz="3.5148003e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="FR_calf"/>
|
||||
<child link="FR_foot"/>
|
||||
</joint>
|
||||
<link name="FR_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="FR_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FR_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FR_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FR_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FR_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="FL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.1881 0.04675 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-0.802851455917" upper="0.802851455917" velocity="21"/>
|
||||
</joint>
|
||||
<link name="FL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0.045 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.00541 -0.00074 6e-06"/>
|
||||
<mass value="0.510299"/>
|
||||
<inertia ixx="0.00030528937" ixy="-7.788013e-06" ixz="2.2016e-07" iyy="0.000590894859" iyz="-1.7175e-08" izz="0.000396594572"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0.08 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="FL_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FL_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.08 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-1.0471975512" upper="4.18879020479" velocity="21"/>
|
||||
</joint>
|
||||
<link name="FL_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/thigh.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003468 -0.018947 -0.032736"/>
|
||||
<mass value="0.898919"/>
|
||||
<inertia ixx="0.005395867678" ixy="1.02809e-07" ixz="0.000337529085" iyy="0.005142451046" iyz="-5.816563e-06" izz="0.00102478732"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="FL_thigh"/>
|
||||
<child link="FL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-2.69653369433" upper="-0.916297857297" velocity="21"/>
|
||||
</joint>
|
||||
<link name="FL_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006286 0.001307 -0.122269"/>
|
||||
<mass value="0.158015"/>
|
||||
<inertia ixx="0.003607648222" ixy="1.494971e-06" ixz="-0.000132778525" iyy="0.003626771492" iyz="-2.8638535e-05" izz="3.5148003e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="FL_calf"/>
|
||||
<child link="FL_foot"/>
|
||||
</joint>
|
||||
<link name="FL_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="FL_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FL_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="FL_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="FL_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="FL_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="RR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.1881 -0.04675 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-0.802851455917" upper="0.802851455917" velocity="21"/>
|
||||
</joint>
|
||||
<link name="RR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.14159265359 3.14159265359 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 -0.045 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.00541 0.00074 6e-06"/>
|
||||
<mass value="0.510299"/>
|
||||
<inertia ixx="0.00030528937" ixy="-7.788013e-06" ixz="-2.2016e-07" iyy="0.000590894859" iyz="1.7175e-08" izz="0.000396594572"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 -0.08 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="RR_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="RR_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.08 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-1.0471975512" upper="4.18879020479" velocity="21"/>
|
||||
</joint>
|
||||
<link name="RR_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/thigh_mirror.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003468 0.018947 -0.032736"/>
|
||||
<mass value="0.898919"/>
|
||||
<inertia ixx="0.005395867678" ixy="-1.02809e-07" ixz="0.000337529085" iyy="0.005142451046" iyz="5.816563e-06" izz="0.00102478732"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="RR_thigh"/>
|
||||
<child link="RR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-2.69653369433" upper="-0.916297857297" velocity="21"/>
|
||||
</joint>
|
||||
<link name="RR_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006286 0.001307 -0.122269"/>
|
||||
<mass value="0.158015"/>
|
||||
<inertia ixx="0.003607648222" ixy="1.494971e-06" ixz="-0.000132778525" iyy="0.003626771492" iyz="-2.8638535e-05" izz="3.5148003e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="RR_calf"/>
|
||||
<child link="RR_foot"/>
|
||||
</joint>
|
||||
<link name="RR_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="RR_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RR_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RR_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RR_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RR_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<joint name="RL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.1881 0.04675 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-0.802851455917" upper="0.802851455917" velocity="21"/>
|
||||
</joint>
|
||||
<link name="RL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 3.14159265359 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/hip.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0.045 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.00541 -0.00074 6e-06"/>
|
||||
<mass value="0.510299"/>
|
||||
<inertia ixx="0.00030528937" ixy="7.788013e-06" ixz="-2.2016e-07" iyy="0.000590894859" iyz="-1.7175e-08" izz="0.000396594572"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_hip_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0.08 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_thigh_shoulder"/>
|
||||
</joint>
|
||||
<!-- this link is only for collision -->
|
||||
<link name="RL_thigh_shoulder">
|
||||
<collision>
|
||||
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.032" radius="0.041"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="RL_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.08 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-1.0471975512" upper="4.18879020479" velocity="21"/>
|
||||
</joint>
|
||||
<link name="RL_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/thigh.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.003468 -0.018947 -0.032736"/>
|
||||
<mass value="0.898919"/>
|
||||
<inertia ixx="0.005395867678" ixy="1.02809e-07" ixz="0.000337529085" iyy="0.005142451046" iyz="-5.816563e-06" izz="0.00102478732"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="RL_thigh"/>
|
||||
<child link="RL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="33.5" lower="-2.69653369433" upper="-0.916297857297" velocity="21"/>
|
||||
</joint>
|
||||
<link name="RL_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="../meshes/calf.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.006286 0.001307 -0.122269"/>
|
||||
<mass value="0.158015"/>
|
||||
<inertia ixx="0.003607648222" ixy="1.494971e-06" ixz="-0.000132778525" iyy="0.003626771492" iyz="-2.8638535e-05" izz="3.5148003e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="RL_calf"/>
|
||||
<child link="RL_foot"/>
|
||||
</joint>
|
||||
<link name="RL_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="RL_hip_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_hip_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_hip_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RL_thigh_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_thigh_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_thigh_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="RL_calf_tran">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="RL_calf_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="RL_calf_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
</robot>
|
||||
|
|
@ -0,0 +1,195 @@
|
|||
<mujoco model="go1_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" frictionloss="0.2" />
|
||||
|
||||
</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>
|
||||
|
||||
<visual>
|
||||
<rgba com="0.502 1.0 0 0.5" contactforce="0.98 0.4 0.4 0.7" contactpoint="1.0 1.0 0.6 0.4"/>
|
||||
<scale com="0.2" forcewidth="0.035" 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="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.35">
|
||||
<inertial pos="0.0116053 0.00442221 0.000106692" quat="0.0111438 0.707126 -0.00935374 0.706938" mass="4.801" diaginertia="0.0447997 0.0366257 0.0162187" />
|
||||
<joint type="free" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="trunk" />
|
||||
<geom size="0.13 0.04675 0.057" type="box" rgba="0.913725 0.913725 0.847059 1" />
|
||||
<geom size="0.0005 0.0005 0.0005" pos="-0.01592 -0.06659 -0.00617" type="box" contype="0" conaffinity="0" group="1" rgba="0.8 0 0 0" />
|
||||
<geom size="0.0005 0.0005 0.0005" pos="-0.01592 -0.06659 -0.00617" type="box" rgba="0.8 0 0 0" />
|
||||
<site name="imu" pos="0 0 0"/>
|
||||
|
||||
<body name="FR_hip" pos="0.1881 -0.04675 0">
|
||||
<inertial pos="-0.00406411 -0.0193463 4.50733e-06" quat="0.467526 0.531662 -0.466259 0.530431" mass="0.679292" diaginertia="0.00131334 0.00122648 0.000728484" />
|
||||
<joint name="FR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
|
||||
<geom quat="0 1 0 0" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="hip" />
|
||||
<geom size="0.046 0.02" pos="0 -0.045 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
|
||||
<geom size="0.031 0.02" pos="0 -0.07 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
|
||||
|
||||
<body name="FR_thigh" pos="0 -0.08 0">
|
||||
<inertial pos="-0.003468 0.018947 -0.032736" quat="0.999266 0.00067676 -0.0382978 0.000639813" mass="0.898919" diaginertia="0.00542178 0.00514246 0.000998869" />
|
||||
<joint name="FR_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-1.0472 4.18879" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="thigh_mirror" />
|
||||
<geom size="0.1065 0.01225 0.017" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
|
||||
<body name="FR_calf" pos="0 0 -0.213">
|
||||
<inertial pos="0.00455603 0.0009473 -0.147239" quat="0.762045 0.00970173 0.0180098 0.647201" mass="0.218015" diaginertia="0.00399678 0.00398122 3.99428e-05" />
|
||||
<joint name="FR_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.69653 -0.916298" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
|
||||
<geom size="0.1065 0.008 0.008" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
|
||||
<geom size="0.01" pos="0 0 -0.213" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
|
||||
<geom size="0.02" pos="0 0 -0.213" rgba="0 0 0 1" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="FL_hip" pos="0.1881 0.04675 0">
|
||||
<inertial pos="-0.00406411 0.0193463 4.50733e-06" quat="0.531662 0.467526 -0.530431 0.466259" mass="0.679292" diaginertia="0.00131334 0.00122648 0.000728484" />
|
||||
<joint name="FL_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="hip" />
|
||||
<geom size="0.046 0.02" pos="0 0.045 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
|
||||
<geom size="0.031 0.02" pos="0 0.07 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
|
||||
|
||||
<body name="FL_thigh" pos="0 0.08 0">
|
||||
<inertial pos="-0.003468 -0.018947 -0.032736" quat="0.999266 -0.00067676 -0.0382978 -0.000639813" mass="0.898919" diaginertia="0.00542178 0.00514246 0.000998869" />
|
||||
<joint name="FL_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-1.0472 4.18879" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="thigh" />
|
||||
<geom size="0.1065 0.01225 0.017" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
|
||||
<body name="FL_calf" pos="0 0 -0.213">
|
||||
<inertial pos="0.00455603 0.0009473 -0.147239" quat="0.762045 0.00970173 0.0180098 0.647201" mass="0.218015" diaginertia="0.00399678 0.00398122 3.99428e-05" />
|
||||
<joint name="FL_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.69653 -0.916298" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
|
||||
<geom size="0.1065 0.008 0.008" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
|
||||
<geom size="0.01" pos="0 0 -0.213" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
|
||||
<geom size="0.02" pos="0 0 -0.213" rgba="0 0 0 1" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="RR_hip" pos="-0.1881 -0.04675 0">
|
||||
<inertial pos="0.00406411 -0.0193463 4.50733e-06" quat="0.530431 0.466259 -0.531662 0.467526" mass="0.679292" diaginertia="0.00131334 0.00122648 0.000728484" />
|
||||
<joint name="RR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
|
||||
<geom quat="0 0 0 -1" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="hip" />
|
||||
<geom size="0.046 0.02" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 1" />
|
||||
<geom size="0.046 0.02" pos="0 -0.045 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
|
||||
<geom size="0.031 0.02" pos="0 -0.07 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
|
||||
|
||||
<body name="RR_thigh" pos="0 -0.08 0">
|
||||
<inertial pos="-0.003468 0.018947 -0.032736" quat="0.999266 0.00067676 -0.0382978 0.000639813" mass="0.898919" diaginertia="0.00542178 0.00514246 0.000998869" />
|
||||
<joint name="RR_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-1.0472 4.18879" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="thigh_mirror" />
|
||||
<geom size="0.1065 0.01225 0.017" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
|
||||
<body name="RR_calf" pos="0 0 -0.213">
|
||||
<inertial pos="0.00455603 0.0009473 -0.147239" quat="0.762045 0.00970173 0.0180098 0.647201" mass="0.218015" diaginertia="0.00399678 0.00398122 3.99428e-05" />
|
||||
<joint name="RR_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.69653 -0.916298" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
|
||||
<geom size="0.1065 0.008 0.008" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
|
||||
<geom size="0.01" pos="0 0 -0.213" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
|
||||
<geom size="0.02" pos="0 0 -0.213" rgba="0 0 0 1" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="RL_hip" pos="-0.1881 0.04675 0">
|
||||
<inertial pos="0.00406411 0.0193463 4.50733e-06" quat="0.466259 0.530431 -0.467526 0.531662" mass="0.679292" diaginertia="0.00131334 0.00122648 0.000728484" />
|
||||
<joint name="RL_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
|
||||
<geom quat="0 0 1 0" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="hip" />
|
||||
<geom size="0.046 0.02" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 1" />
|
||||
<geom size="0.046 0.02" pos="0 0.045 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
|
||||
<geom size="0.031 0.02" pos="0 0.07 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
|
||||
|
||||
<body name="RL_thigh" pos="0 0.08 0">
|
||||
<inertial pos="-0.003468 -0.018947 -0.032736" quat="0.999266 -0.00067676 -0.0382978 -0.000639813" mass="0.898919" diaginertia="0.00542178 0.00514246 0.000998869" />
|
||||
<joint name="RL_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-1.0472 4.18879" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="thigh" />
|
||||
<geom size="0.1065 0.01225 0.017" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
|
||||
<body name="RL_calf" pos="0 0 -0.213">
|
||||
<inertial pos="0.00455603 0.0009473 -0.147239" quat="0.762045 0.00970173 0.0180098 0.647201" mass="0.218015" diaginertia="0.00399678 0.00398122 3.99428e-05" />
|
||||
<joint name="RL_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.69653 -0.916298" />
|
||||
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
|
||||
<geom size="0.1065 0.008 0.008" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
|
||||
<geom size="0.01" pos="0 0 -0.213" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
|
||||
<geom size="0.02" pos="0 0 -0.213" 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"/>
|
||||
|
||||
<accelerometer name="Body_Acc" site="imu"/>
|
||||
|
||||
<gyro name="Body_Gyro" site="imu"/>
|
||||
|
||||
<framepos name="Body_Pos" objtype=site objname="imu"/>
|
||||
|
||||
<framequat name="Body_Quat" objtype=site objname="imu"/>
|
||||
|
||||
|
||||
</sensor>
|
||||
</mujoco>
|
|
@ -41,7 +41,7 @@
|
|||
</material>
|
||||
|
||||
<link name="world"/>
|
||||
<joint name="" type="floating">
|
||||
<joint name="floating_base" type="floating">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="trunk"/>
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
<light castshadow="false" diffuse="1 1 1"/>
|
||||
<motor ctrlrange="-40.0 40.0" ctrllimited="true"/>
|
||||
<camera fovy="60"/>
|
||||
<joint damping="0.01" armature="0.01"/>
|
||||
<joint damping="0.01" armature="0.01" frictionloss="0.2" />
|
||||
|
||||
</default>
|
||||
|
||||
|
@ -21,6 +21,11 @@
|
|||
<mesh name="thigh" file="thigh.stl" />
|
||||
</asset>
|
||||
|
||||
<visual>
|
||||
<rgba com="0.502 1.0 0 0.5" contactforce="0.98 0.4 0.4 0.7" contactpoint="1.0 1.0 0.6 0.4"/>
|
||||
<scale com="0.2" forcewidth="0.035" contactwidth="0.10" contactheight="0.04"/>
|
||||
</visual>
|
||||
|
||||
<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"/>
|
||||
|
@ -31,11 +36,13 @@
|
|||
<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">
|
||||
<body name="trunk" pos="0 0 0.4">
|
||||
<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 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" />
|
||||
<site name="imu" pos="0 0 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" />
|
||||
|
@ -51,6 +58,7 @@
|
|||
<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" />
|
||||
<geom size="0.027 0.014" pos="0 0 -0.25" quat="0.707107 0.707107 0 0" rgba="0.913725 0.913725 0.847059 0" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
|
@ -69,6 +77,7 @@
|
|||
<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" />
|
||||
<geom size="0.027 0.014" pos="0 0 -0.25" quat="0.707107 0.707107 0 0" rgba="0.913725 0.913725 0.847059 0" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
|
@ -87,6 +96,7 @@
|
|||
<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" />
|
||||
<geom size="0.027 0.014" pos="0 0 -0.25" quat="0.707107 0.707107 0 0" rgba="0.913725 0.913725 0.847059 0" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
|
@ -105,6 +115,7 @@
|
|||
<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" />
|
||||
<geom size="0.027 0.014" pos="0 0 -0.25" quat="0.707107 0.707107 0 0" rgba="0.913725 0.913725 0.847059 0" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
|
@ -154,6 +165,14 @@
|
|||
<jointvel name="RL_thigh_vel" joint="RL_thigh_joint"/>
|
||||
<jointvel name="RL_calf_vel" joint="RL_calf_joint"/>
|
||||
|
||||
<accelerometer name="Body_Acc" site="imu"/>
|
||||
|
||||
<gyro name="Body_Gyro" site="imu"/>
|
||||
|
||||
<framepos name="Body_Pos" objtype=site objname="imu"/>
|
||||
|
||||
<framequat name="Body_Quat" objtype=site objname="imu"/>
|
||||
|
||||
</sensor>
|
||||
|
||||
</mujoco>
|
Loading…
Reference in New Issue