D1 arm assets added and ocp example updated.

This commit is contained in:
Rooholla-KhorramBakht 2024-12-03 11:06:54 -05:00
parent 4aca24c569
commit b6bdcda7e3
45 changed files with 2782 additions and 135 deletions

View File

@ -43,16 +43,17 @@ SHELL ["conda", "run", "-n", "base", "/bin/bash", "-c"]
ENV CONDA_PREFIX /opt/conda ENV CONDA_PREFIX /opt/conda
# Cheange the ROS2 RMW to CycloneDDS as instructed by Unitree # Cheange the ROS2 RMW to CycloneDDS as instructed by Unitree
RUN cd / && git clone https://github.com/unitreerobotics/unitree_ros2 && cd /unitree_ros2/cyclonedds_ws/src && \ # RUN cd / && git clone https://github.com/unitreerobotics/unitree_ros2 && cd /unitree_ros2/cyclonedds_ws/src && \
git clone https://github.com/ros2/rmw_cyclonedds -b humble && git clone https://github.com/eclipse-cyclonedds/cyclonedds -b releases/0.10.x &&\ # git clone https://github.com/ros2/rmw_cyclonedds -b humble && git clone https://github.com/eclipse-cyclonedds/cyclonedds -b releases/0.10.x &&\
cd .. && colcon build --packages-select cyclonedds && source /opt/ros/humble/setup.bash && colcon build # cd .. && colcon build --packages-select cyclonedds && source /opt/ros/humble/setup.bash && colcon build
# Install Python dependencies # Install Python dependencies
RUN pip install torch torchvision torchaudio --index-url https://download.pytorch.org/whl/cu118 RUN pip install torch torchvision torchaudio --index-url https://download.pytorch.org/whl/cu118
RUN pip install matplotlib opencv-python proxsuite scipy isort black RUN pip install matplotlib opencv-python proxsuite scipy isort black
RUN pip install warp-lang scikit-learn casadi RUN pip install warp-lang scikit-learn casadi
RUN pip install onnx onnxruntime
RUN pip install cyclonedds pygame pynput onnx onnxruntime jupyter ipykernel meshcat mujoco # RUN pip install cyclonedds pygame pynput jupyter ipykernel
RUN pip install meshcat mujoco
RUN conda install -y -c conda-forge \ RUN conda install -y -c conda-forge \
pinocchio \ pinocchio \
crocoddyl \ crocoddyl \

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@ -0,0 +1,59 @@
<mujoco model="d1_description">
<compiler angle="radian" meshdir="../" autolimits="true"/>
<asset>
<mesh name="base_link" file="d1_assets/stl/base_link.STL"/>
<mesh name="Link1" file="d1_assets/stl/Link1.STL"/>
<mesh name="Link2" file="d1_assets/stl/Link2.STL"/>
<mesh name="Link3" file="d1_assets/stl/Link3.STL"/>
<mesh name="Link4" file="d1_assets/stl/Link4.STL"/>
<mesh name="Link5" file="d1_assets/stl/Link5.STL"/>
<mesh name="Link6" file="d1_assets/stl/Link6.STL"/>
<mesh name="Link7_1" file="d1_assets/stl/Link7_1.STL"/>
<mesh name="Link7_2" file="d1_assets/stl/Link7_2.STL"/>
</asset>
<worldbody>
<geom type="mesh" rgba="1 1 1 1" mesh="base_link"/>
<body name="Link1" pos="0 0 0.0533" quat="-3.67321e-06 0 0 -1">
<inertial pos="0.0024649 0.00010517 0.032696" quat="0.999717 -0.0236435 -0.00169588 -0.00221682" mass="0.13174" diaginertia="6.72365e-05 5.41766e-05 4.66199e-05"/>
<joint name="Joint1" pos="0 0 0" axis="0 0 1" range="-2.35 2.35"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link1"/>
<body name="Link2" pos="0 0.028 0.0563" quat="-2.59734e-06 -2.59735e-06 -0.707108 -0.707105">
<inertial pos="0.0002018 0.19201 -0.027007" quat="0.706347 0.707865 -0.00093681 0.00051949" mass="0.20213" diaginertia="0.00025682 0.000229681 6.33062e-05"/>
<joint name="Joint2" pos="0 0 0" axis="0 0 -1" range="-1.57 1.57"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link2"/>
<body name="Link3" pos="0 0.2693 0.0009">
<inertial pos="0.015164 0.044482 -0.027461" quat="0.690744 0.690771 -0.151176 -0.151179" mass="0.0629" diaginertia="1.84718e-05 1.4964e-05 1.13662e-05"/>
<joint name="Joint3" pos="0 0 0" axis="0 0 -1" range="-1.57 1.57"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link3"/>
<body name="Link4" pos="0.0577 0.042 -0.0275" quat="0.499998 -0.5 0.500002 -0.5">
<inertial pos="-0.00029556 -0.00016104 0.091339" quat="0.999998 -3.46195e-05 0.00170171 0.00102754" mass="0.083332" diaginertia="3.93083e-05 3.4378e-05 1.15967e-05"/>
<joint name="Joint4" pos="0 0 0" axis="0 0 1" range="-2.35 2.35"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link4"/>
<body name="Link5" pos="-0.0001 -0.0237 0.14018" quat="0.499998 0.5 -0.5 0.500002">
<inertial pos="0.040573 0.0062891 -0.023838" quat="0.706153 0.706691 -0.0310982 -0.0311281" mass="0.053817" diaginertia="1.31069e-05 1.1049e-05 8.59523e-06"/>
<joint name="Joint5" pos="0 0 0" axis="0 0 -1" range="-1.57 1.57"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link5"/>
<body name="Link6" pos="0.0825 -0.0010782 -0.023822" quat="0.499998 -0.5 0.500002 -0.5">
<inertial pos="-0.0068528 -3.9973e-06 0.039705" quat="0.494949 0.495288 -0.504676 0.504992" mass="0.077892" diaginertia="4.8843e-05 3.8232e-05 1.7707e-05"/>
<joint name="Joint6" pos="0 0 0" axis="0 0 -1" range="-2.35 2.35"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link6"/>
<body name="Link7_1" pos="-0.0056012 -0.029636 0.0706" quat="0.499848 -0.50015 -0.49985 -0.500152">
<inertial pos="0.018927 0.006 0.012082" quat="0 0.677073 0 0.735916" mass="0.015046" diaginertia="2.62715e-06 2.0229e-06 1.25975e-06"/>
<joint name="Joint7_1" pos="0 0 0" axis="0 0 -1" type="slide" range="0 0.03"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link7_1"/>
</body>
<body name="Link7_2" pos="-0.0056388 0.02964 0.0706" quat="0.500148 0.49985 -0.50015 0.499852">
<inertial pos="0.018927 -0.006 0.012082" quat="0 0.677073 0 0.735916" mass="0.015046" diaginertia="2.62715e-06 2.0229e-06 1.25975e-06"/>
<joint name="Joint7_2" pos="0 0 0" axis="0 0 1" type="slide" range="-0.03 0"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link7_2"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
</mujoco>

View File

@ -1,5 +1,5 @@
<mujoco model="go2"> <mujoco model="go2">
<compiler angle="radian" meshdir="assets" autolimits="true"/> <compiler angle="radian" meshdir="../" autolimits="true"/>
<option cone="elliptic" impratio="100"/> <option cone="elliptic" impratio="100"/>
@ -46,22 +46,22 @@
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/> <texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/> <material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
<mesh file="base_0.obj"/> <mesh file="go2_assets/obj/base_0.obj"/>
<mesh file="base_1.obj"/> <mesh file="go2_assets/obj/base_1.obj"/>
<mesh file="base_2.obj"/> <mesh file="go2_assets/obj/base_2.obj"/>
<mesh file="base_3.obj"/> <mesh file="go2_assets/obj/base_3.obj"/>
<mesh file="base_4.obj"/> <mesh file="go2_assets/obj/base_4.obj"/>
<mesh file="hip_0.obj"/> <mesh file="go2_assets/obj/hip_0.obj"/>
<mesh file="hip_1.obj"/> <mesh file="go2_assets/obj/hip_1.obj"/>
<mesh file="thigh_0.obj"/> <mesh file="go2_assets/obj/thigh_0.obj"/>
<mesh file="thigh_1.obj"/> <mesh file="go2_assets/obj/thigh_1.obj"/>
<mesh file="thigh_mirror_0.obj"/> <mesh file="go2_assets/obj/thigh_mirror_0.obj"/>
<mesh file="thigh_mirror_1.obj"/> <mesh file="go2_assets/obj/thigh_mirror_1.obj"/>
<mesh file="calf_0.obj"/> <mesh file="go2_assets/obj/calf_0.obj"/>
<mesh file="calf_1.obj"/> <mesh file="go2_assets/obj/calf_1.obj"/>
<mesh file="calf_mirror_0.obj"/> <mesh file="go2_assets/obj/calf_mirror_0.obj"/>
<mesh file="calf_mirror_1.obj"/> <mesh file="go2_assets/obj/calf_mirror_1.obj"/>
<mesh file="foot.obj"/> <mesh file="go2_assets/obj/foot.obj"/>
</asset> </asset>
<worldbody> <worldbody>

View File

@ -0,0 +1,306 @@
<mujoco model="go2">
<compiler angle="radian" meshdir="../" autolimits="true"/>
<option cone="elliptic" impratio="100"/>
<default>
<default class="go2">
<geom friction="0.6" margin="0.001" condim="1"/>
<joint axis="0 1 0" damping="0" armature="0.01" frictionloss="0.2"/>
<motor ctrlrange="-23.7 23.7"/>
<default class="abduction">
<joint axis="1 0 0" range="-1.0472 1.0472"/>
</default>
<default class="hip">
<default class="front_hip">
<joint range="-1.5708 3.4907"/>
</default>
<default class="back_hip">
<joint range="-0.5236 4.5379"/>
</default>
</default>
<default class="knee">
<joint range="-2.7227 -0.83776"/>
<motor ctrlrange="-45.43 45.43"/>
</default>
<default class="arm">
<joint range="-2.7227 -0.83776"/>
<motor ctrlrange="-45.43 45.43"/>
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision">
<geom group="3"/>
<default class="foot">
<geom size="0.022" 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>
<hfield name="terrain" nrow="300" ncol="300" size="5 5 1. 0.1"/>
<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"/>
<texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" height="3072"/>
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
<mesh file="go2_assets/obj/base_0.obj"/>
<mesh file="go2_assets/obj/base_1.obj"/>
<mesh file="go2_assets/obj/base_2.obj"/>
<mesh file="go2_assets/obj/base_3.obj"/>
<mesh file="go2_assets/obj/base_4.obj"/>
<mesh file="go2_assets/obj/hip_0.obj"/>
<mesh file="go2_assets/obj/hip_1.obj"/>
<mesh file="go2_assets/obj/thigh_0.obj"/>
<mesh file="go2_assets/obj/thigh_1.obj"/>
<mesh file="go2_assets/obj/thigh_mirror_0.obj"/>
<mesh file="go2_assets/obj/thigh_mirror_1.obj"/>
<mesh file="go2_assets/obj/calf_0.obj"/>
<mesh file="go2_assets/obj/calf_1.obj"/>
<mesh file="go2_assets/obj/calf_mirror_0.obj"/>
<mesh file="go2_assets/obj/calf_mirror_1.obj"/>
<mesh file="go2_assets/obj/foot.obj"/>
<mesh name="base_link" file="d1_assets/stl/base_link.STL"/>
<mesh name="Link1" file="d1_assets/stl/Link1.STL"/>
<mesh name="Link2" file="d1_assets/stl/Link2.STL"/>
<mesh name="Link3" file="d1_assets/stl/Link3.STL"/>
<mesh name="Link4" file="d1_assets/stl/Link4.STL"/>
<mesh name="Link5" file="d1_assets/stl/Link5.STL"/>
<mesh name="Link6" file="d1_assets/stl/Link6.STL"/>
<mesh name="Link7_1" file="d1_assets/stl/Link7_1.STL"/>
<mesh name="Link7_2" file="d1_assets/stl/Link7_2.STL"/>
</asset>
<worldbody>
<geom name="heightfield" pos="0.0 0.0 -0.1" type="hfield" hfield="terrain"/>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
<body name="base" pos="0 0 0.445" childclass="go2">
<light pos="0.0 0.0 2.5" />
<camera name="front_camera" mode="fixed" pos="0.321618 0.033305 0.081622" euler="1.57079632679 0. 0." resolution="640 480" fovy="45."/>
<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.1881 0.04675 0.057" type="box" class="collision"/>
<geom size="0.05 0.045" pos="0.285 0 0.01" type="cylinder" 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="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" type="cylinder" 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="front_hip"/>
<geom mesh="thigh_mirror_0" material="metal" class="visual"/>
<geom mesh="thigh_mirror_1" material="gray" class="visual"/>
<geom size="0.1065 0.01225 0.017" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" 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" type="cylinder" class="collision"/>
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" type="cylinder" class="collision"/>
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
<geom name="FR" class="foot"/>
<site name="FR_foot" pos="0 0 -0.213" size="0.02"/>
</body>
</body>
</body>
<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" type="cylinder" 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="front_hip"/>
<geom mesh="thigh_0" material="metal" class="visual"/>
<geom mesh="thigh_1" material="gray" class="visual"/>
<geom size="0.1065 0.01225 0.017" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" 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" type="cylinder" class="collision"/>
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" type="cylinder" class="collision"/>
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
<geom name="FL" class="foot"/>
<site name="FL_foot" pos="0 0 -0.213" size="0.02"/>
</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" type="cylinder" 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="back_hip"/>
<geom mesh="thigh_mirror_0" material="metal" class="visual"/>
<geom mesh="thigh_mirror_1" material="gray" class="visual"/>
<geom size="0.1065 0.01225 0.017" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" 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" type="cylinder" class="collision"/>
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" type="cylinder" class="collision"/>
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
<geom name="RR" class="foot"/>
<site name="RR_foot" pos="0 0 -0.213" size="0.02"/>
</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" type="cylinder" 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="back_hip"/>
<geom mesh="thigh_0" material="metal" class="visual"/>
<geom mesh="thigh_1" material="gray" class="visual"/>
<geom size="0.1065 0.01225 0.017" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" 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" type="cylinder" class="collision"/>
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" type="cylinder" class="collision"/>
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
<geom name="RL" class="foot"/>
<site name="RL_foot" pos="0 0 -0.213" size="0.02"/>
</body>
</body>
</body>
<body name="d1_base" pos="0 0 0.0533" quat="1. 0. 0. 0.">
<geom type="mesh" rgba="1 1 1 1" mesh="base_link"/>
<body name="Link1" pos="0 0 0.0533" quat="-3.67321e-06 0 0 -1">
<inertial pos="0.0024649 0.00010517 0.032696" quat="0.999717 -0.0236435 -0.00169588 -0.00221682" mass="0.13174" diaginertia="6.72365e-05 5.41766e-05 4.66199e-05"/>
<joint name="Joint1" pos="0 0 0" axis="0 0 1" range="-2.35 2.35"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link1"/>
<body name="Link2" pos="0 0.028 0.0563" quat="-2.59734e-06 -2.59735e-06 -0.707108 -0.707105">
<inertial pos="0.0002018 0.19201 -0.027007" quat="0.706347 0.707865 -0.00093681 0.00051949" mass="0.20213" diaginertia="0.00025682 0.000229681 6.33062e-05"/>
<joint name="Joint2" pos="0 0 0" axis="0 0 -1" range="-1.57 1.57"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link2"/>
<body name="Link3" pos="0 0.2693 0.0009">
<inertial pos="0.015164 0.044482 -0.027461" quat="0.690744 0.690771 -0.151176 -0.151179" mass="0.0629" diaginertia="1.84718e-05 1.4964e-05 1.13662e-05"/>
<joint name="Joint3" pos="0 0 0" axis="0 0 -1" range="-1.57 1.57"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link3"/>
<body name="Link4" pos="0.0577 0.042 -0.0275" quat="0.499998 -0.5 0.500002 -0.5">
<inertial pos="-0.00029556 -0.00016104 0.091339" quat="0.999998 -3.46195e-05 0.00170171 0.00102754" mass="0.083332" diaginertia="3.93083e-05 3.4378e-05 1.15967e-05"/>
<joint name="Joint4" pos="0 0 0" axis="0 0 1" range="-2.35 2.35"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link4"/>
<body name="Link5" pos="-0.0001 -0.0237 0.14018" quat="0.499998 0.5 -0.5 0.500002">
<inertial pos="0.040573 0.0062891 -0.023838" quat="0.706153 0.706691 -0.0310982 -0.0311281" mass="0.053817" diaginertia="1.31069e-05 1.1049e-05 8.59523e-06"/>
<joint name="Joint5" pos="0 0 0" axis="0 0 -1" range="-1.57 1.57"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link5"/>
<body name="Link6" pos="0.0825 -0.0010782 -0.023822" quat="0.499998 -0.5 0.500002 -0.5">
<inertial pos="-0.0068528 -3.9973e-06 0.039705" quat="0.494949 0.495288 -0.504676 0.504992" mass="0.077892" diaginertia="4.8843e-05 3.8232e-05 1.7707e-05"/>
<joint name="Joint6" pos="0 0 0" axis="0 0 -1" range="-2.35 2.35"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link6"/>
<body name="Link7_1" pos="-0.0056012 -0.029636 0.0706" quat="0.499848 -0.50015 -0.49985 -0.500152">
<inertial pos="0.018927 0.006 0.012082" quat="0 0.677073 0 0.735916" mass="0.015046" diaginertia="2.62715e-06 2.0229e-06 1.25975e-06"/>
<joint name="Joint7_1" pos="0 0 0" axis="0 0 -1" type="slide" range="0 0.03"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link7_1"/>
</body>
<body name="Link7_2" pos="-0.0056388 0.02964 0.0706" quat="0.500148 0.49985 -0.50015 0.499852">
<inertial pos="0.018927 -0.006 0.012082" quat="0 0.677073 0 0.735916" mass="0.015046" diaginertia="2.62715e-06 2.0229e-06 1.25975e-06"/>
<joint name="Joint7_2" pos="0 0 0" axis="0 0 1" type="slide" range="-0.03 0"/>
<geom type="mesh" rgba="1 1 1 1" mesh="Link7_2"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
<actuator>
<motor class="abduction" name="FR_hip" joint="FR_hip_joint"/>
<motor class="hip" name="FR_thigh" joint="FR_thigh_joint"/>
<motor class="knee" name="FR_calf" joint="FR_calf_joint"/>
<motor class="abduction" name="FL_hip" joint="FL_hip_joint"/>
<motor class="hip" name="FL_thigh" joint="FL_thigh_joint"/>
<motor class="knee" name="FL_calf" joint="FL_calf_joint"/>
<motor class="abduction" name="RR_hip" joint="RR_hip_joint"/>
<motor class="hip" name="RR_thigh" joint="RR_thigh_joint"/>
<motor class="knee" name="RR_calf" joint="RR_calf_joint"/>
<motor class="abduction" name="RL_hip" joint="RL_hip_joint"/>
<motor class="hip" name="RL_thigh" joint="RL_thigh_joint"/>
<motor class="knee" name="RL_calf" joint="RL_calf_joint"/>
<motor class="arm" name="Link1" joint="Joint1"/>
<motor class="arm" name="Link2" joint="Joint2"/>
<motor class="arm" name="Link3" joint="Joint3"/>
<motor class="arm" name="Link4" joint="Joint4"/>
<motor class="arm" name="Link5" joint="Joint5"/>
<motor class="arm" name="Link6" joint="Joint6"/>
<motor class="arm" name="Link7_1" joint="Joint7_1"/>
<motor class="arm" name="Link7_2" joint="Joint7_2"/>
</actuator>
<sensor>
<!-- IMU -->
<accelerometer name="imu_accel" site="imu"/>
<gyro name="imu_gyro" site="imu"/>
<!-- Contact sensors for the feet -->
<touch name="FR_foot_contact" site="FR_foot"/>
<touch name="FL_foot_contact" site="RL_foot"/>
<touch name="RR_foot_contact" site="RR_foot"/>
<touch name="RL_foot_contact" site="RL_foot"/>
</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 0 0 0 0 0 0 0 0"
ctrl="0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0 0 0 0 0 0 0"/>
</keyframe>
</mujoco>

Binary file not shown.

View File

@ -0,0 +1,511 @@
<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
Commit Version: 1.6.0-4-g7f85cfe Build Version: 1.6.7995.38578
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
name="d1_description">
<link
name="base_link">
<inertial>
<origin
xyz="-0.00048697 -2.9605E-12 0.017142"
rpy="0 0 0" />
<mass
value="0.077233" />
<inertia
ixx="0.00010316"
ixy="-1.0285E-14"
ixz="2.0449E-07"
iyy="0.00011888"
iyz="7.3026E-15"
izz="0.00018362" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/base_link.STL" />
</geometry>
</collision>
</link>
<link
name="Link1">
<inertial>
<origin
xyz="0.0024649 0.00010517 0.032696"
rpy="0 0 0" />
<mass
value="0.13174" />
<inertia
ixx="6.7236E-05"
ixy="-5.5664E-08"
ixz="7.0454E-08"
iyy="5.416E-05"
iyz="-3.5709E-07"
izz="4.6637E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link1.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link1.STL" />
</geometry>
</collision>
</link>
<joint
name="Joint1"
type="revolute">
<origin
xyz="0 0 0.0533"
rpy="0 0 -3.1416" />
<parent
link="base_link" />
<child
link="Link1" />
<axis
xyz="0 0 1" />
<limit
lower="-2.35"
upper="2.35"
effort="0"
velocity="0" />
</joint>
<link
name="Link2">
<inertial>
<origin
xyz="0.0002018 0.19201 -0.027007"
rpy="0 0 0" />
<mass
value="0.20213" />
<inertia
ixx="0.00025682"
ixy="-1.139E-07"
ixz="5.5667E-08"
iyy="6.3307E-05"
iyz="-3.5717E-07"
izz="0.00022968" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link2.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="stl/Link2.STL" />
</geometry>
</collision>
</link>
<joint
name="Joint2"
type="revolute">
<origin
xyz="0 0.028 0.0563"
rpy="1.5708 0 -3.1416" />
<parent
link="Link1" />
<child
link="Link2" />
<axis
xyz="0 0 -1" />
<limit
lower="-1.57"
upper="1.57"
effort="0"
velocity="0" />
</joint>
<link
name="Link3">
<inertial>
<origin
xyz="0.015164 0.044482 -0.027461"
rpy="0 0 0" />
<mass
value="0.0629" />
<inertia
ixx="1.7232E-05"
ixy="-2.6967E-06"
ixz="-9.4911E-11"
iyy="1.2606E-05"
iyz="-9.9169E-11"
izz="1.4964E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link3.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link3.STL" />
</geometry>
</collision>
</link>
<joint
name="Joint3"
type="revolute">
<origin
xyz="0 0.2693 0.0009"
rpy="0 0 0" />
<parent
link="Link2" />
<child
link="Link3" />
<axis
xyz="0 0 -1" />
<limit
lower="-1.57"
upper="1.57"
effort="0"
velocity="0" />
</joint>
<link
name="Link4">
<inertial>
<origin
xyz="-0.00029556 -0.00016104 0.091339"
rpy="0 0 0" />
<mass
value="0.083332" />
<inertia
ixx="3.9308E-05"
ixy="1.0126E-08"
ixz="-9.4316E-08"
iyy="3.4378E-05"
iyz="-1.6915E-09"
izz="1.1597E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link4.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link4.STL" />
</geometry>
</collision>
</link>
<joint
name="Joint4"
type="revolute">
<origin
xyz="0.0577 0.042 -0.0275"
rpy="-1.5708 0 -1.5708" />
<parent
link="Link3" />
<child
link="Link4" />
<axis
xyz="0 0 1" />
<limit
lower="-2.35"
upper="2.35"
effort="0"
velocity="0" />
</joint>
<link
name="Link5">
<inertial>
<origin
xyz="0.040573 0.0062891 -0.023838"
rpy="0 0 0" />
<mass
value="0.053817" />
<inertia
ixx="1.3072E-05"
ixy="-3.9511E-07"
ixz="-3.1889E-10"
iyy="8.6301E-06"
iyz="-1.8416E-09"
izz="1.1049E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link5.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link5.STL" />
</geometry>
</collision>
</link>
<joint
name="Joint5"
type="revolute">
<origin
xyz="-0.0001 -0.0237 0.14018"
rpy="1.5708 -1.5708 0" />
<parent
link="Link4" />
<child
link="Link5" />
<axis
xyz="0 0 -1" />
<limit
lower="-1.57"
upper="1.57"
effort="0"
velocity="0" />
</joint>
<link
name="Link6">
<inertial>
<origin
xyz="-0.0068528 -3.9973E-06 0.039705"
rpy="0 0 0" />
<mass
value="0.077892" />
<inertia
ixx="3.8236E-05"
ixy="1.3465E-08"
ixz="-2.0614E-07"
iyy="1.7707E-05"
iyz="-6.7117E-10"
izz="4.8839E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link6.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link6.STL" />
</geometry>
</collision>
</link>
<joint
name="Joint6"
type="revolute">
<origin
xyz="0.0825 -0.0010782 -0.023822"
rpy="-1.5708 0 -1.5708" />
<parent
link="Link5" />
<child
link="Link6" />
<axis
xyz="0 0 -1" />
<limit
lower="-2.35"
upper="2.35"
effort="0"
velocity="0" />
</joint>
<link
name="Link7_1">
<inertial>
<origin
xyz="0.018927 0.006 0.012082"
rpy="0 0 0" />
<mass
value="0.015046" />
<inertia
ixx="1.2692E-06"
ixy="7.7441E-20"
ixz="-1.133E-07"
iyy="2.0229E-06"
iyz="1.2044E-20"
izz="2.6177E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link7_1.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link7_1.STL" />
</geometry>
</collision>
</link>
<joint
name="Joint7_1"
type="prismatic">
<origin
xyz="-0.0056012 -0.029636 0.0706"
rpy="-1.5714 -1.5708 0" />
<parent
link="Link6" />
<child
link="Link7_1" />
<axis
xyz="0 0 -1" />
<limit
lower="0"
upper="0.03"
effort="0"
velocity="0" />
</joint>
<link
name="Link7_2">
<inertial>
<origin
xyz="0.018927 -0.006 0.012082"
rpy="0 0 0" />
<mass
value="0.015046" />
<inertia
ixx="1.2692E-06"
ixy="-7.8273E-20"
ixz="-1.133E-07"
iyy="2.0229E-06"
iyz="-1.2122E-20"
izz="2.6177E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link7_2.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="../stl/Link7_2.STL" />
</geometry>
</collision>
</link>
<joint
name="Joint7_2"
type="prismatic">
<origin
xyz="-0.0056388 0.02964 0.0706"
rpy="1.5702 -1.5708 0" />
<parent
link="Link6" />
<child
link="Link7_2" />
<axis
xyz="0 0 1" />
<limit
lower="-0.03"
upper="0"
effort="0"
velocity="0" />
</joint>
</robot>

View File

@ -69,7 +69,7 @@ Stephen Brawner (brawner@gmail.com)
<child link="Head_lower"/> <child link="Head_lower"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="FL_hip"> <link name="FL_HAA">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="-0.0054 0.00194 -0.000105"/> <origin rpy="0 0 0" xyz="-0.0054 0.00194 -0.000105"/>
<mass value="0.678"/> <mass value="0.678"/>
@ -91,15 +91,15 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> --> </collision> -->
</link> </link>
<joint name="FL_hip_joint" type="revolute"> <joint name="FL_HAA_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.1934 0.0465 0"/> <origin rpy="0 0 0" xyz="0.1934 0.0465 0"/>
<parent link="base_link"/> <parent link="base_link"/>
<child link="FL_hip"/> <child link="FL_HAA"/>
<axis xyz="1 0 0"/> <axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/> <dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/> <limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/>
</joint> </joint>
<link name="FL_thigh"> <link name="FL_HFE">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="-0.00374 -0.0223 -0.0327"/> <origin rpy="0 0 0" xyz="-0.00374 -0.0223 -0.0327"/>
<mass value="1.152"/> <mass value="1.152"/>
@ -121,15 +121,15 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FL_thigh_joint" type="revolute"> <joint name="FL_HFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.0955 0"/> <origin rpy="0 0 0" xyz="0 0.0955 0"/>
<parent link="FL_hip"/> <parent link="FL_HAA"/>
<child link="FL_thigh"/> <child link="FL_HFE"/>
<axis xyz="0 1 0"/> <axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/> <dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-1.5708" upper="3.4907" velocity="30.1"/> <limit effort="23.7" lower="-1.5708" upper="3.4907" velocity="30.1"/>
</joint> </joint>
<link name="FL_calf"> <link name="FL_KFE">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.00548 -0.000975 -0.115"/> <origin rpy="0 0 0" xyz="0.00548 -0.000975 -0.115"/>
<mass value="0.154"/> <mass value="0.154"/>
@ -151,15 +151,15 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FL_calf_joint" type="revolute"> <joint name="FL_KFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.213"/> <origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="FL_thigh"/> <parent link="FL_HFE"/>
<child link="FL_calf"/> <child link="FL_KFE"/>
<axis xyz="0 1 0"/> <axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/> <dynamics damping="0" friction="0"/>
<limit effort="45.43" lower="-2.7227" upper="-0.83776" velocity="15.70"/> <limit effort="45.43" lower="-2.7227" upper="-0.83776" velocity="15.70"/>
</joint> </joint>
<link name="FL_calflower"> <link name="FL_KFElower">
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
@ -167,13 +167,13 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FL_calflower_joint" type="fixed"> <joint name="FL_KFElower_joint" type="fixed">
<origin rpy="0 0.05 0" xyz="0.020 0 -0.148"/> <origin rpy="0 0.05 0" xyz="0.020 0 -0.148"/>
<parent link="FL_calf"/> <parent link="FL_KFE"/>
<child link="FL_calflower"/> <child link="FL_KFElower"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="FL_calflower1"> <link name="FL_KFElower1">
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
@ -181,13 +181,13 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FL_calflower1_joint" type="fixed"> <joint name="FL_KFElower1_joint" type="fixed">
<origin rpy="0 0.48 0" xyz="-0.01 0 -0.04"/> <origin rpy="0 0.48 0" xyz="-0.01 0 -0.04"/>
<parent link="FL_calflower"/> <parent link="FL_KFElower"/>
<child link="FL_calflower1"/> <child link="FL_KFElower1"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="FL_foot"> <link name="FL_FOOT">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.04"/> <mass value="0.04"/>
@ -209,13 +209,13 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint dont_collapse="true" name="FL_foot_joint" type="fixed"> <joint dont_collapse="true" name="FL_FOOT_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.213"/> <origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="FL_calf"/> <parent link="FL_KFE"/>
<child link="FL_foot"/> <child link="FL_FOOT"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="FR_hip"> <link name="FR_HAA">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="-0.0054 -0.00194 -0.000105"/> <origin rpy="0 0 0" xyz="-0.0054 -0.00194 -0.000105"/>
<mass value="0.678"/> <mass value="0.678"/>
@ -237,15 +237,15 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> --> </collision> -->
</link> </link>
<joint name="FR_hip_joint" type="revolute"> <joint name="FR_HAA_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.1934 -0.0465 0"/> <origin rpy="0 0 0" xyz="0.1934 -0.0465 0"/>
<parent link="base_link"/> <parent link="base_link"/>
<child link="FR_hip"/> <child link="FR_HAA"/>
<axis xyz="1 0 0"/> <axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/> <dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/> <limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/>
</joint> </joint>
<link name="FR_thigh"> <link name="FR_HFE">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="-0.00374 0.0223 -0.0327"/> <origin rpy="0 0 0" xyz="-0.00374 0.0223 -0.0327"/>
<mass value="1.152"/> <mass value="1.152"/>
@ -267,15 +267,15 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FR_thigh_joint" type="revolute"> <joint name="FR_HFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.0955 0"/> <origin rpy="0 0 0" xyz="0 -0.0955 0"/>
<parent link="FR_hip"/> <parent link="FR_HAA"/>
<child link="FR_thigh"/> <child link="FR_HFE"/>
<axis xyz="0 1 0"/> <axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/> <dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-1.5708" upper="3.4907" velocity="30.1"/> <limit effort="23.7" lower="-1.5708" upper="3.4907" velocity="30.1"/>
</joint> </joint>
<link name="FR_calf"> <link name="FR_KFE">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.00548 0.000975 -0.115"/> <origin rpy="0 0 0" xyz="0.00548 0.000975 -0.115"/>
<mass value="0.154"/> <mass value="0.154"/>
@ -297,15 +297,15 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FR_calf_joint" type="revolute"> <joint name="FR_KFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.213"/> <origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="FR_thigh"/> <parent link="FR_HFE"/>
<child link="FR_calf"/> <child link="FR_KFE"/>
<axis xyz="0 1 0"/> <axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/> <dynamics damping="0" friction="0"/>
<limit effort="45.43" lower="-2.7227" upper="-0.83776" velocity="15.70"/> <limit effort="45.43" lower="-2.7227" upper="-0.83776" velocity="15.70"/>
</joint> </joint>
<link name="FR_calflower"> <link name="FR_KFElower">
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
@ -313,13 +313,13 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FR_calflower_joint" type="fixed"> <joint name="FR_KFElower_joint" type="fixed">
<origin rpy="0 0.05 0" xyz="0.020 0 -0.148"/> <origin rpy="0 0.05 0" xyz="0.020 0 -0.148"/>
<parent link="FR_calf"/> <parent link="FR_KFE"/>
<child link="FR_calflower"/> <child link="FR_KFElower"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="FR_calflower1"> <link name="FR_KFElower1">
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
@ -327,13 +327,13 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="FR_calflower1_joint" type="fixed"> <joint name="FR_KFElower1_joint" type="fixed">
<origin rpy="0 0.48 0" xyz="-0.01 0 -0.04"/> <origin rpy="0 0.48 0" xyz="-0.01 0 -0.04"/>
<parent link="FR_calflower"/> <parent link="FR_KFElower"/>
<child link="FR_calflower1"/> <child link="FR_KFElower1"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="FR_foot"> <link name="FR_FOOT">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.04"/> <mass value="0.04"/>
@ -355,13 +355,13 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint dont_collapse="true" name="FR_foot_joint" type="fixed"> <joint dont_collapse="true" name="FR_FOOT_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.213"/> <origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="FR_calf"/> <parent link="FR_KFE"/>
<child link="FR_foot"/> <child link="FR_FOOT"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="RL_hip"> <link name="HL_HAA">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.0054 0.00194 -0.000105"/> <origin rpy="0 0 0" xyz="0.0054 0.00194 -0.000105"/>
<mass value="0.678"/> <mass value="0.678"/>
@ -383,15 +383,15 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> --> </collision> -->
</link> </link>
<joint name="RL_hip_joint" type="revolute"> <joint name="HL_HAA_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.1934 0.0465 0"/> <origin rpy="0 0 0" xyz="-0.1934 0.0465 0"/>
<parent link="base_link"/> <parent link="base_link"/>
<child link="RL_hip"/> <child link="HL_HAA"/>
<axis xyz="1 0 0"/> <axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/> <dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/> <limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/>
</joint> </joint>
<link name="RL_thigh"> <link name="HL_HFE">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="-0.00374 -0.0223 -0.0327"/> <origin rpy="0 0 0" xyz="-0.00374 -0.0223 -0.0327"/>
<mass value="1.152"/> <mass value="1.152"/>
@ -413,15 +413,15 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RL_thigh_joint" type="revolute"> <joint name="HL_HFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.0955 0"/> <origin rpy="0 0 0" xyz="0 0.0955 0"/>
<parent link="RL_hip"/> <parent link="HL_HAA"/>
<child link="RL_thigh"/> <child link="HL_HFE"/>
<axis xyz="0 1 0"/> <axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/> <dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-0.5236" upper="4.5379" velocity="30.1"/> <limit effort="23.7" lower="-0.5236" upper="4.5379" velocity="30.1"/>
</joint> </joint>
<link name="RL_calf"> <link name="HL_KFE">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.00548 -0.000975 -0.115"/> <origin rpy="0 0 0" xyz="0.00548 -0.000975 -0.115"/>
<mass value="0.154"/> <mass value="0.154"/>
@ -443,15 +443,15 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RL_calf_joint" type="revolute"> <joint name="HL_KFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.213"/> <origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="RL_thigh"/> <parent link="HL_HFE"/>
<child link="RL_calf"/> <child link="HL_KFE"/>
<axis xyz="0 1 0"/> <axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/> <dynamics damping="0" friction="0"/>
<limit effort="45.43" lower="-2.7227" upper="-0.83776" velocity="15.70"/> <limit effort="45.43" lower="-2.7227" upper="-0.83776" velocity="15.70"/>
</joint> </joint>
<link name="RL_calflower"> <link name="HL_KFElower">
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
@ -459,13 +459,13 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RL_calflower_joint" type="fixed"> <joint name="HL_KFElower_joint" type="fixed">
<origin rpy="0 0.05 0" xyz="0.020 0 -0.148"/> <origin rpy="0 0.05 0" xyz="0.020 0 -0.148"/>
<parent link="RL_calf"/> <parent link="HL_KFE"/>
<child link="RL_calflower"/> <child link="HL_KFElower"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="RL_calflower1"> <link name="HL_KFElower1">
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
@ -473,13 +473,13 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RL_calflower1_joint" type="fixed"> <joint name="HL_KFElower1_joint" type="fixed">
<origin rpy="0 0.48 0" xyz="-0.01 0 -0.04"/> <origin rpy="0 0.48 0" xyz="-0.01 0 -0.04"/>
<parent link="RL_calflower"/> <parent link="HL_KFElower"/>
<child link="RL_calflower1"/> <child link="HL_KFElower1"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="RL_foot"> <link name="HL_FOOT">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.04"/> <mass value="0.04"/>
@ -501,13 +501,13 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint dont_collapse="true" name="RL_foot_joint" type="fixed"> <joint dont_collapse="true" name="HL_FOOT_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.213"/> <origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="RL_calf"/> <parent link="HL_KFE"/>
<child link="RL_foot"/> <child link="HL_FOOT"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="RR_hip"> <link name="HR_HAA">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.0054 -0.00194 -0.000105"/> <origin rpy="0 0 0" xyz="0.0054 -0.00194 -0.000105"/>
<mass value="0.678"/> <mass value="0.678"/>
@ -529,15 +529,15 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> --> </collision> -->
</link> </link>
<joint name="RR_hip_joint" type="revolute"> <joint name="HR_HAA_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.1934 -0.0465 0"/> <origin rpy="0 0 0" xyz="-0.1934 -0.0465 0"/>
<parent link="base_link"/> <parent link="base_link"/>
<child link="RR_hip"/> <child link="HR_HAA"/>
<axis xyz="1 0 0"/> <axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/> <dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/> <limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/>
</joint> </joint>
<link name="RR_thigh"> <link name="HR_HFE">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="-0.00374 0.0223 -0.0327"/> <origin rpy="0 0 0" xyz="-0.00374 0.0223 -0.0327"/>
<mass value="1.152"/> <mass value="1.152"/>
@ -559,15 +559,15 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RR_thigh_joint" type="revolute"> <joint name="HR_HFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.0955 0"/> <origin rpy="0 0 0" xyz="0 -0.0955 0"/>
<parent link="RR_hip"/> <parent link="HR_HAA"/>
<child link="RR_thigh"/> <child link="HR_HFE"/>
<axis xyz="0 1 0"/> <axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/> <dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-0.5236" upper="4.5379" velocity="30.1"/> <limit effort="23.7" lower="-0.5236" upper="4.5379" velocity="30.1"/>
</joint> </joint>
<link name="RR_calf"> <link name="HR_KFE">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0.00548 0.000975 -0.115"/> <origin rpy="0 0 0" xyz="0.00548 0.000975 -0.115"/>
<mass value="0.154"/> <mass value="0.154"/>
@ -589,15 +589,15 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RR_calf_joint" type="revolute"> <joint name="HR_KFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.213"/> <origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="RR_thigh"/> <parent link="HR_HFE"/>
<child link="RR_calf"/> <child link="HR_KFE"/>
<axis xyz="0 1 0"/> <axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/> <dynamics damping="0" friction="0"/>
<limit effort="45.43" lower="-2.7227" upper="-0.83776" velocity="15.70"/> <limit effort="45.43" lower="-2.7227" upper="-0.83776" velocity="15.70"/>
</joint> </joint>
<link name="RR_calflower"> <link name="HR_KFElower">
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
@ -605,13 +605,13 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RR_calflower_joint" type="fixed"> <joint name="HR_KFElower_joint" type="fixed">
<origin rpy="0 0.05 0" xyz="0.020 0 -0.148"/> <origin rpy="0 0.05 0" xyz="0.020 0 -0.148"/>
<parent link="RR_calf"/> <parent link="HR_KFE"/>
<child link="RR_calflower"/> <child link="HR_KFElower"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="RR_calflower1"> <link name="HR_KFElower1">
<collision> <collision>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
@ -619,13 +619,13 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint name="RR_calflower1_joint" type="fixed"> <joint name="HR_KFElower1_joint" type="fixed">
<origin rpy="0 0.48 0" xyz="-0.01 0 -0.04"/> <origin rpy="0 0.48 0" xyz="-0.01 0 -0.04"/>
<parent link="RR_calflower"/> <parent link="HR_KFElower"/>
<child link="RR_calflower1"/> <child link="HR_KFElower1"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="RR_foot"> <link name="HR_FOOT">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.04"/> <mass value="0.04"/>
@ -647,10 +647,10 @@ Stephen Brawner (brawner@gmail.com)
</geometry> </geometry>
</collision> </collision>
</link> </link>
<joint dont_collapse="true" name="RR_foot_joint" type="fixed"> <joint dont_collapse="true" name="HR_FOOT_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.213"/> <origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="RR_calf"/> <parent link="HR_KFE"/>
<child link="RR_foot"/> <child link="HR_FOOT"/>
<axis xyz="0 0 0"/> <axis xyz="0 0 0"/>
</joint> </joint>
<link name="imu_link"> <link name="imu_link">

File diff suppressed because it is too large Load Diff

View File

@ -349,15 +349,22 @@ class Go2Sim:
except: except:
raise Exception(f'Could not load heightmap. Make sure the heigh_map is a 2D numpy array') raise Exception(f'Could not load heightmap. Make sure the heigh_map is a 2D numpy array')
def reset(self): def reset(self, q0=None):
self.q_nominal = np.hstack( if q0 is None:
[self.pos0.squeeze(), self.rot0.squeeze(), self.q0.squeeze()] self.q_nominal = np.hstack(
) [self.pos0.squeeze(), self.rot0.squeeze(), self.q0.squeeze()]
)
else:
assert q0.shape == (19,), 'Invalid q0 shape. The shape should be (19,)'
self.q_nominal = q0
self.data.qpos = self.q_nominal self.data.qpos = self.q_nominal
self.data.qvel = np.zeros(18) self.data.qvel = np.zeros(18)
self.ex_sum=0 self.ex_sum=0
self.ey_sum=0 self.ey_sum=0
self.e_omega_sum=0 self.e_omega_sum=0
mujoco.mj_step(self.model, self.data)
if self.render:
self.viewer.sync()
def standUpReset(self): def standUpReset(self):
self.q0 = self.standing_q self.q0 = self.standing_q

File diff suppressed because one or more lines are too long

6
examples/MUJOCO_LOG.TXT Normal file
View File

@ -0,0 +1,6 @@
Tue Dec 3 15:37:57 2024
WARNING: Nan, Inf or huge value in QACC at DOF 3. The simulation is unstable. Time = 0.8500.
Tue Dec 3 15:45:56 2024
WARNING: Nan, Inf or huge value in QACC at DOF 20. The simulation is unstable. Time = 0.7940.

BIN
examples/test.xml Normal file

Binary file not shown.

View File

@ -21,4 +21,4 @@ install_requires =
# pynput # pynput
# pin # pin
# mujoco # mujoco
cyclonedds # cyclonedds