Behron 60aaea751f Finished fixing merge conflicts and touched up camera settings.
More merge conflicts. Taking main changes then will integrate mine.
2025-04-10 13:20:26 -06:00

250 lines
13 KiB
XML

<mujoco model="go2">
<compiler angle="radian" meshdir="assets" autolimits="true"/>
<option cone="pyramidal" impratio="100" iterations="1" ls_iterations="5">
<flag eulerdamp="disable"/>
</option>
<default>
<default class="go2">
<geom friction="0.6" margin="0.001" condim="1"/>
<joint axis="0 1 0" damping="2" armature="0.01"/>
<general forcerange="-24 24" biastype="affine" gainprm="50 0 0" biasprm="0 -50 -0.5"/>
<default class="abduction">
<joint axis="1 0 0" range="-1.0472 1.0472"/>
<general ctrlrange="-0.9472 0.9472"/>
</default>
<default class="hip">
<joint range="-1.5708 3.4907"/>
<general ctrlrange="-1.4 2.5"/>
</default>
<default class="knee">
<joint range="-2.7227 -0.83776"/>
<general ctrlrange="-2.6227 -0.84776"/>
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="go2foot">
<site group="1" pos="-0.002 0 -0.213"/>
<geom rgba="0.231373 0.380392 0.705882 1"/>
</default>
<default class="collision">
<geom group="3"/>
<default class="foot">
<geom size="0.0175" pos="-0.002 0 -0.213" priority="1" solimp="0.015 1 0.031" condim="6"
friction="0.8 0.02 0.01"/>
</default>
</default>
</default>
</default>
<asset>
<material name="metal" rgba=".9 .95 .95 1"/>
<material name="black" rgba="0 0 0 1"/>
<material name="white" rgba="1 1 1 1"/>
<material name="gray" rgba="0.671705 0.692426 0.774270 1"/>
<mesh file="base_0.obj"/>
<mesh file="base_1.obj"/>
<mesh file="base_2.obj"/>
<mesh file="base_3.obj"/>
<mesh file="base_4.obj"/>
<mesh file="hip_0.obj"/>
<mesh file="hip_1.obj"/>
<mesh file="thigh_0.obj"/>
<mesh file="thigh_1.obj"/>
<mesh file="thigh_mirror_0.obj"/>
<mesh file="thigh_mirror_1.obj"/>
<mesh file="calf_0.obj"/>
<mesh file="calf_1.obj"/>
<mesh file="calf_mirror_0.obj"/>
<mesh file="calf_mirror_1.obj"/>
<mesh file="foot.obj"/>
</asset>
<worldbody>
<body name="base" pos="0 0 0.445" childclass="go2">
<camera name="track" pos="0.846 -1.465 0.916" xyaxes="0.866 0.500 0.000 -0.171 0.296 0.940" mode="trackcom"/>
<inertial pos="0.021112 0 -0.005366" quat="-0.000543471 0.713435 -0.00173769 0.700719" mass="6.921"
diaginertia="0.107027 0.0980771 0.0244531"/>
<freejoint/>
<geom mesh="base_0" material="black" class="visual"/>
<geom mesh="base_1" material="black" class="visual"/>
<geom mesh="base_2" material="black" class="visual"/>
<geom mesh="base_3" material="white" class="visual"/>
<geom mesh="base_4" material="gray" class="visual"/>
<geom size="0.057 0.04675 0.057" class="collision"/>
<geom size="0.05 0.045" pos="0.285 0 0.01" class="collision"/>
<geom size="0.047" pos="0.293 0 -0.06" class="collision"/>
<site name="imu" pos="-0.02557 0 0.04232"/>
<body name="FL_hip" pos="0.1934 0.0465 0">
<inertial pos="-0.0054 0.00194 -0.000105" quat="0.497014 0.499245 0.505462 0.498237" mass="0.678"
diaginertia="0.00088403 0.000596003 0.000479967"/>
<joint name="FL_hip_joint" class="abduction"/>
<geom mesh="hip_0" material="metal" class="visual"/>
<geom mesh="hip_1" material="gray" class="visual"/>
<geom size="0.046 0.02" pos="0 0.08 0" quat="1 1 0 0" class="collision"/>
<body name="FL_thigh" pos="0 0.0955 0">
<inertial pos="-0.00374 -0.0223 -0.0327" quat="0.829533 0.0847635 -0.0200632 0.551623" mass="1.152"
diaginertia="0.00594973 0.00584149 0.000878787"/>
<joint name="FL_thigh_joint" class="hip"/>
<geom mesh="thigh_0" material="metal" class="visual"/>
<geom mesh="thigh_1" material="gray" class="visual"/>
<geom size="0.017 0.01225 0.017" pos="-0.015 0 -0.1955" quat="0.707107 0 0.707107 0" class="collision"/>
<body name="FL_calf" pos="0 0 -0.213">
<inertial pos="0.00629595 -0.000622121 -0.141417" quat="0.710672 0.00154099 -0.00450087 0.703508"
mass="0.241352" diaginertia="0.0014901 0.00146356 5.31397e-05"/>
<joint name="FL_calf_joint" class="knee"/>
<geom mesh="calf_0" material="gray" class="visual"/>
<geom mesh="calf_1" material="black" class="visual"/>
<geom size="0.012 0.06" pos="0.008 0 -0.06" quat="0.994493 0 -0.104807 0" class="collision"/>
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" class="collision"/>
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
<geom name="FL" class="foot"/>
<site name="FL_foot" class="go2foot"/>
</body>
</body>
</body>
<body name="FR_hip" pos="0.1934 -0.0465 0">
<inertial pos="-0.0054 -0.00194 -0.000105" quat="0.498237 0.505462 0.499245 0.497014" mass="0.678"
diaginertia="0.00088403 0.000596003 0.000479967"/>
<joint name="FR_hip_joint" class="abduction"/>
<geom mesh="hip_0" material="metal" class="visual" quat="4.63268e-05 1 0 0"/>
<geom mesh="hip_1" material="gray" class="visual" quat="4.63268e-05 1 0 0"/>
<geom size="0.046 0.02" pos="0 -0.08 0" quat="0.707107 0.707107 0 0" class="collision"/>
<body name="FR_thigh" pos="0 -0.0955 0">
<inertial pos="-0.00374 0.0223 -0.0327" quat="0.551623 -0.0200632 0.0847635 0.829533" mass="1.152"
diaginertia="0.00594973 0.00584149 0.000878787"/>
<joint name="FR_thigh_joint" class="hip"/>
<geom mesh="thigh_mirror_0" material="metal" class="visual"/>
<geom mesh="thigh_mirror_1" material="gray" class="visual"/>
<geom size="0.017 0.01225 0.017" pos="-0.015 0 -0.1955" quat="0.707107 0 0.707107 0" class="collision"/>
<body name="FR_calf" pos="0 0 -0.213">
<inertial pos="0.00629595 0.000622121 -0.141417" quat="0.703508 -0.00450087 0.00154099 0.710672"
mass="0.241352" diaginertia="0.0014901 0.00146356 5.31397e-05"/>
<joint name="FR_calf_joint" class="knee"/>
<geom mesh="calf_mirror_0" material="gray" class="visual"/>
<geom mesh="calf_mirror_1" material="black" class="visual"/>
<geom size="0.013 0.06" pos="0.01 0 -0.06" quat="0.995004 0 -0.0998334 0" class="collision"/>
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" class="collision"/>
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
<geom name="FR" class="foot"/>
<site name="FR_foot" class="go2foot"/>
</body>
</body>
</body>
<body name="RL_hip" pos="-0.1934 0.0465 0">
<inertial pos="0.0054 0.00194 -0.000105" quat="0.505462 0.498237 0.497014 0.499245" mass="0.678"
diaginertia="0.00088403 0.000596003 0.000479967"/>
<joint name="RL_hip_joint" class="abduction"/>
<geom mesh="hip_0" material="metal" class="visual" quat="4.63268e-05 0 1 0"/>
<geom mesh="hip_1" material="gray" class="visual" quat="4.63268e-05 0 1 0"/>
<geom size="0.046 0.02" pos="0 0.08 0" quat="0.707107 0.707107 0 0" class="collision"/>
<body name="RL_thigh" pos="0 0.0955 0">
<inertial pos="-0.00374 -0.0223 -0.0327" quat="0.829533 0.0847635 -0.0200632 0.551623" mass="1.152"
diaginertia="0.00594973 0.00584149 0.000878787"/>
<joint name="RL_thigh_joint" class="hip"/>
<geom mesh="thigh_0" material="metal" class="visual"/>
<geom mesh="thigh_1" material="gray" class="visual"/>
<geom size="0.017 0.01225 0.017" pos="-0.015 0 -0.1955" quat="0.707107 0 0.707107 0" class="collision"/>
<body name="RL_calf" pos="0 0 -0.213">
<inertial pos="0.00629595 -0.000622121 -0.141417" quat="0.710672 0.00154099 -0.00450087 0.703508"
mass="0.241352" diaginertia="0.0014901 0.00146356 5.31397e-05"/>
<joint name="RL_calf_joint" class="knee"/>
<geom mesh="calf_0" material="gray" class="visual"/>
<geom mesh="calf_1" material="black" class="visual"/>
<geom size="0.013 0.06" pos="0.01 0 -0.06" quat="0.995004 0 -0.0998334 0" class="collision"/>
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" class="collision"/>
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
<geom name="RL" class="foot"/>
<site name="RL_foot" class="go2foot"/>
</body>
</body>
</body>
<body name="RR_hip" pos="-0.1934 -0.0465 0">
<inertial pos="0.0054 -0.00194 -0.000105" quat="0.499245 0.497014 0.498237 0.505462" mass="0.678"
diaginertia="0.00088403 0.000596003 0.000479967"/>
<joint name="RR_hip_joint" class="abduction"/>
<geom mesh="hip_0" material="metal" class="visual" quat="2.14617e-09 4.63268e-05 4.63268e-05 -1"/>
<geom mesh="hip_1" material="gray" class="visual" quat="2.14617e-09 4.63268e-05 4.63268e-05 -1"/>
<geom size="0.046 0.02" pos="0 -0.08 0" quat="0.707107 0.707107 0 0" class="collision"/>
<body name="RR_thigh" pos="0 -0.0955 0">
<inertial pos="-0.00374 0.0223 -0.0327" quat="0.551623 -0.0200632 0.0847635 0.829533" mass="1.152"
diaginertia="0.00594973 0.00584149 0.000878787"/>
<joint name="RR_thigh_joint" class="hip"/>
<geom mesh="thigh_mirror_0" material="metal" class="visual"/>
<geom mesh="thigh_mirror_1" material="gray" class="visual"/>
<geom size="0.017 0.01225 0.017" pos="-0.015 0 -0.1955" quat="0.707107 0 0.707107 0" class="collision"/>
<body name="RR_calf" pos="0 0 -0.213">
<inertial pos="0.00629595 0.000622121 -0.141417" quat="0.703508 -0.00450087 0.00154099 0.710672"
mass="0.241352" diaginertia="0.0014901 0.00146356 5.31397e-05"/>
<joint name="RR_calf_joint" class="knee"/>
<geom mesh="calf_mirror_0" material="gray" class="visual"/>
<geom mesh="calf_mirror_1" material="black" class="visual"/>
<geom size="0.013 0.06" pos="0.01 0 -0.06" quat="0.995004 0 -0.0998334 0" class="collision"/>
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" class="collision"/>
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
<geom name="RR" class="foot"/>
<site name="RR_foot" class="go2foot"/>
</body>
</body>
</body>
</body>
</worldbody>
<actuator>
<general class="abduction" name="FL_hip" joint="FL_hip_joint"/>
<general class="hip" name="FL_thigh" joint="FL_thigh_joint"/>
<general class="knee" name="FL_calf" joint="FL_calf_joint"/>
<general class="abduction" name="FR_hip" joint="FR_hip_joint"/>
<general class="hip" name="FR_thigh" joint="FR_thigh_joint"/>
<general class="knee" name="FR_calf" joint="FR_calf_joint"/>
<general class="abduction" name="RL_hip" joint="RL_hip_joint"/>
<general class="hip" name="RL_thigh" joint="RL_thigh_joint"/>
<general class="knee" name="RL_calf" joint="RL_calf_joint"/>
<general class="abduction" name="RR_hip" joint="RR_hip_joint"/>
<general class="hip" name="RR_thigh" joint="RR_thigh_joint"/>
<general class="knee" name="RR_calf" joint="RR_calf_joint"/>
</actuator>
<sensor>
<jointpos joint="FL_hip_joint" name="abduction_front_left_pos"/>
<jointpos joint="FL_thigh_joint" name="hip_front_left_pos"/>
<jointpos joint="FL_calf_joint" name="knee_front_left_pos"/>
<jointpos joint="RL_hip_joint" name="abduction_hind_left_pos"/>
<jointpos joint="RL_thigh_joint" name="hip_hind_left_pos"/>
<jointpos joint="RL_calf_joint" name="knee_hind_left_pos"/>
<jointpos joint="FR_hip_joint" name="abduction_front_right_pos"/>
<jointpos joint="FR_thigh_joint" name="hip_front_right_pos"/>
<jointpos joint="FR_calf_joint" name="knee_front_right_pos"/>
<jointpos joint="RR_hip_joint" name="abduction_hind_right_pos"/>
<jointpos joint="RR_thigh_joint" name="hip_hind_right_pos"/>
<jointpos joint="RR_calf_joint" name="knee_hind_right_pos"/>
<jointvel joint="FL_hip_joint" name="abduction_front_left_vel"/>
<jointvel joint="FL_thigh_joint" name="hip_front_left_vel"/>
<jointvel joint="FL_calf_joint" name="knee_front_left_vel"/>
<jointvel joint="RL_hip_joint" name="abduction_hind_left_vel"/>
<jointvel joint="RL_thigh_joint" name="hip_hind_left_vel"/>
<jointvel joint="RL_calf_joint" name="knee_hind_left_vel"/>
<jointvel joint="FR_hip_joint" name="abduction_front_right_vel"/>
<jointvel joint="FR_thigh_joint" name="hip_front_right_vel"/>
<jointvel joint="FR_calf_joint" name="knee_front_right_vel"/>
<jointvel joint="RR_hip_joint" name="abduction_hind_right_vel"/>
<jointvel joint="RR_thigh_joint" name="hip_hind_right_vel"/>
<jointvel joint="RR_calf_joint" name="knee_hind_right_vel"/>
<gyro site="imu" name="gyro"/>
<accelerometer site="imu" name="accelerometer"/>
<framequat objtype="site" objname="imu" name="orientation"/>
<framepos objtype="site" objname="imu" name="global_position"/>
<framelinvel objtype="site" objname="imu" name="global_linvel"/>
<frameangvel objtype="site" objname="imu" name="global_angvel"/>
</sensor>
<keyframe>
<key name="home" qpos="0 0 0.27 1 0 0 0 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8"
ctrl="0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8"/>
</keyframe>
</mujoco>