-
Notifications
You must be signed in to change notification settings - Fork 148
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Add Unitree H1 Walk task #336
Open
AntoSave
wants to merge
26
commits into
google-deepmind:main
Choose a base branch
from
AntoSave:feature-h1-walk
base: main
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
Open
Changes from all commits
Commits
Show all changes
26 commits
Select commit
Hold shift + click to select a range
6d54f28
[REF] Increased max message size for grpc servers
AntoSave 7d67c12
[ADD] Add Unitree H1 Walk task
AntoSave 5b89bc5
[ADD] Add utility for visualization in mujoco
AntoSave 3d3017f
[ADD] Add utility for plotting live graphs
AntoSave 22147db
[ADD] Add utility for live parameter editing
AntoSave e256ed2
[REF] Model checkpoint for H1 walk
AntoSave 12a9a21
[DOC] Fix comment
AntoSave cbb6cf3
[ADD] Point plotting in mujoco
AntoSave 2edb239
[ADD] python script for h1 walk tuning
AntoSave 97d7924
[ADD] Add a new cost term which penalizes the feet crossing
AntoSave cfc9ad6
[REM] Useless files for the PR
AntoSave f902df5
[REM] H1 walk baseline task, as it shouldn't be in the PR
AntoSave 994054c
[REM] Useless comments
AntoSave d45fde7
[DOC] Updated comments
AntoSave 45b15c8
Merge branch 'main' of https://github.com/google-deepmind/mujoco_mpc …
AntoSave 813e622
Merge branch 'google-deepmind-main' into feature-h1-walk
AntoSave cb20fdb
[REF] Reduced agent horizon to 0.4s
AntoSave 636f8b7
[REF] Changed agent integrator to 'implicitfast'
AntoSave 9dfcc14
[DOC] Added spaces after '//'
AntoSave d73cd6a
[REM] Removed useless function and comments
AntoSave 47228ab
[REF] Formatted code with 'clang-format' vscode extension
AntoSave 65132ee
[REF] Removed links to local machine in patch file
AntoSave 9954bc0
- [ADD] Robot now follows orientation reference (mocap quaternion) af…
AntoSave 0e81d03
- [FIX] Fixed a bug in the "Face goal" residual calculation
AntoSave 0282b27
[DOC] Updated comment
AntoSave 6cb23e4
[REF] 'Face Goal' now takes into account the four orientations separa…
AntoSave File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,187 @@ | ||
diff --git a/h1.xml b/h1.xml | ||
--- a/h1.xml | ||
+++ b/h1.xml | ||
@@ -1,5 +1,5 @@ | ||
<mujoco model="h1"> | ||
- <compiler angle="radian" meshdir="assets" autolimits="true"/> | ||
+ <compiler angle="radian" meshdir="../assets" autolimits="true"/> | ||
|
||
<statistic meansize="0.05"/> | ||
|
||
@@ -62,84 +62,86 @@ | ||
diaginertia="0.0490211 0.0445821 0.00824619"/> | ||
<freejoint/> | ||
<geom class="visual" mesh="pelvis"/> | ||
- <body name="left_hip_yaw_link" pos="0 0.0875 -0.1742"> | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Maybe check to see if this diff can be smaller? |
||
- <inertial pos="-0.04923 0.0001 0.0072" quat="0.69699 0.219193 0.233287 0.641667" mass="2.244" | ||
- diaginertia="0.00304494 0.00296885 0.00189201"/> | ||
- <joint name="left_hip_yaw" axis="0 0 1" range="-0.43 0.43"/> | ||
- <geom class="visual" mesh="left_hip_yaw_link"/> | ||
- <geom size="0.06 0.035" pos="-0.067 0 0" quat="0.707123 0 0.70709 0" type="cylinder" class="collision"/> | ||
- <body name="left_hip_roll_link" pos="0.039468 0 0"> | ||
- <inertial pos="-0.0058 -0.00319 -9e-05" quat="0.0438242 0.70721 -0.0729075 0.701867" mass="2.232" | ||
- diaginertia="0.00243264 0.00225325 0.00205492"/> | ||
- <joint name="left_hip_roll" axis="1 0 0" range="-0.43 0.43"/> | ||
- <geom class="visual" mesh="left_hip_roll_link"/> | ||
- <geom class="collision" type="cylinder" size="0.05 0.03" quat="1 1 0 0" pos="0 -0.02 0"/> | ||
- <body name="left_hip_pitch_link" pos="0 0.11536 0"> | ||
- <inertial pos="0.00746 -0.02346 -0.08193" quat="0.979828 0.0513522 -0.0169854 -0.192382" mass="4.152" | ||
- diaginertia="0.0829503 0.0821457 0.00510909"/> | ||
- <joint name="left_hip_pitch" axis="0 1 0" range="-1.57 1.57"/> | ||
- <geom class="visual" mesh="left_hip_pitch_link"/> | ||
- <geom class="collision" type="capsule" size="0.03" fromto="0.02 0 -0.4 -0.02 0 0.02"/> | ||
- <geom class="collision" type="capsule" size="0.03" fromto="0.02 0 -0.4 0.02 0 0.02"/> | ||
- <geom class="collision" type="cylinder" size="0.05 0.02" quat="1 1 0 0" pos="0 -0.07 0"/> | ||
- <body name="left_knee_link" pos="0 0 -0.4"> | ||
- <inertial pos="-0.00136 -0.00512 -0.1384" quat="0.626132 -0.034227 -0.0416277 0.777852" mass="1.721" | ||
- diaginertia="0.0125237 0.0123104 0.0019428"/> | ||
- <joint name="left_knee" axis="0 1 0" range="-0.26 2.05"/> | ||
- <geom class="visual" mesh="left_knee_link"/> | ||
- <geom class="collision" type="capsule" size="0.025" fromto="0.02 0 -0.4 0.02 0 0"/> | ||
- <geom class="collision" type="sphere" size="0.05" pos="0 0 -0.115"/> | ||
- <body name="left_ankle_link" pos="0 0 -0.4"> | ||
- <inertial pos="0.06722 0.00015 -0.04497" quat="0.489101 0.503197 0.565782 0.432972" mass="0.446" | ||
- diaginertia="0.00220848 0.00218961 0.000214202"/> | ||
- <joint name="left_ankle" axis="0 1 0" range="-0.87 0.52"/> | ||
- <geom class="visual" mesh="left_ankle_link"/> | ||
- <geom class="foot1"/> | ||
- <geom class="foot2"/> | ||
- <geom class="foot3"/> | ||
- </body> | ||
+ <body name="legs"><!--ADDED--> | ||
+ <body name="left_hip_yaw_link" pos="0 0.0875 -0.1742"> | ||
+ <inertial pos="-0.04923 0.0001 0.0072" quat="0.69699 0.219193 0.233287 0.641667" mass="2.244" | ||
+ diaginertia="0.00304494 0.00296885 0.00189201"/> | ||
+ <joint name="left_hip_yaw" axis="0 0 1" range="-0.43 0.43"/> | ||
+ <geom class="visual" mesh="left_hip_yaw_link"/> | ||
+ <geom size="0.06 0.035" pos="-0.067 0 0" quat="0.707123 0 0.70709 0" type="cylinder" class="collision"/> | ||
+ <body name="left_hip_roll_link" pos="0.039468 0 0"> | ||
+ <inertial pos="-0.0058 -0.00319 -9e-05" quat="0.0438242 0.70721 -0.0729075 0.701867" mass="2.232" | ||
+ diaginertia="0.00243264 0.00225325 0.00205492"/> | ||
+ <joint name="left_hip_roll" axis="1 0 0" range="-0.43 0.43"/> | ||
+ <geom class="visual" mesh="left_hip_roll_link"/> | ||
+ <geom class="collision" type="cylinder" size="0.05 0.03" quat="1 1 0 0" pos="0 -0.02 0"/> | ||
+ <body name="left_hip_pitch_link" pos="0 0.11536 0"> | ||
+ <inertial pos="0.00746 -0.02346 -0.08193" quat="0.979828 0.0513522 -0.0169854 -0.192382" mass="4.152" | ||
+ diaginertia="0.0829503 0.0821457 0.00510909"/> | ||
+ <joint name="left_hip_pitch" axis="0 1 0" range="-1.57 1.57"/> | ||
+ <geom class="visual" mesh="left_hip_pitch_link"/> | ||
+ <geom class="collision" type="capsule" size="0.03" fromto="0.02 0 -0.4 -0.02 0 0.02"/> | ||
+ <geom class="collision" type="capsule" size="0.03" fromto="0.02 0 -0.4 0.02 0 0.02"/> | ||
+ <geom class="collision" type="cylinder" size="0.05 0.02" quat="1 1 0 0" pos="0 -0.07 0"/> | ||
+ <body name="left_knee_link" pos="0 0 -0.4"> | ||
+ <inertial pos="-0.00136 -0.00512 -0.1384" quat="0.626132 -0.034227 -0.0416277 0.777852" mass="1.721" | ||
+ diaginertia="0.0125237 0.0123104 0.0019428"/> | ||
+ <joint name="left_knee" axis="0 1 0" range="-0.26 2.05"/> | ||
+ <geom class="visual" mesh="left_knee_link"/> | ||
+ <geom class="collision" type="capsule" size="0.025" fromto="0.02 0 -0.4 0.02 0 0"/> | ||
+ <geom class="collision" type="sphere" size="0.05" pos="0 0 -0.115"/> | ||
+ <body name="left_ankle_link" pos="0 0 -0.4"> | ||
+ <inertial pos="0.06722 0.00015 -0.04497" quat="0.489101 0.503197 0.565782 0.432972" mass="0.446" | ||
+ diaginertia="0.00220848 0.00218961 0.000214202"/> | ||
+ <joint name="left_ankle" axis="0 1 0" range="-0.87 0.52"/> | ||
+ <geom class="visual" mesh="left_ankle_link"/> | ||
+ <geom class="foot1"/> | ||
+ <geom class="foot2"/> | ||
+ <geom class="foot3"/> | ||
+ </body> | ||
+ </body> | ||
+ </body> | ||
</body> | ||
- </body> | ||
</body> | ||
- </body> | ||
- <body name="right_hip_yaw_link" pos="0 -0.0875 -0.1742"> | ||
- <inertial pos="-0.04923 -0.0001 0.0072" quat="0.641667 0.233287 0.219193 0.69699" mass="2.244" | ||
- diaginertia="0.00304494 0.00296885 0.00189201"/> | ||
- <joint name="right_hip_yaw" axis="0 0 1" range="-0.43 0.43"/> | ||
- <geom class="visual" mesh="right_hip_yaw_link"/> | ||
- <geom size="0.06 0.035" pos="-0.067 0 0" quat="0.707123 0 0.70709 0" type="cylinder" class="collision"/> | ||
- <body name="right_hip_roll_link" pos="0.039468 0 0"> | ||
- <inertial pos="-0.0058 0.00319 -9e-05" quat="-0.0438242 0.70721 0.0729075 0.701867" mass="2.232" | ||
- diaginertia="0.00243264 0.00225325 0.00205492"/> | ||
- <joint name="right_hip_roll" axis="1 0 0" range="-0.43 0.43"/> | ||
- <geom class="visual" mesh="right_hip_roll_link"/> | ||
- <geom class="collision" type="cylinder" size="0.05 0.03" quat="1 1 0 0" pos="0 0.02 0"/> | ||
- <body name="right_hip_pitch_link" pos="0 -0.11536 0"> | ||
- <inertial pos="0.00746 0.02346 -0.08193" quat="0.979828 -0.0513522 -0.0169854 0.192382" mass="4.152" | ||
- diaginertia="0.0829503 0.0821457 0.00510909"/> | ||
- <joint name="right_hip_pitch" axis="0 1 0" range="-1.57 1.57"/> | ||
- <geom class="visual" mesh="right_hip_pitch_link"/> | ||
- <geom class="collision" type="capsule" size="0.03" fromto="0.02 0 -0.4 -0.02 0 0.02"/> | ||
- <geom class="collision" type="capsule" size="0.03" fromto="0.02 0 -0.4 0.02 0 0.02"/> | ||
- <geom class="collision" type="cylinder" size="0.05 0.02" quat="1 1 0 0" pos="0 0.07 0"/> | ||
- <body name="right_knee_link" pos="0 0 -0.4"> | ||
- <inertial pos="-0.00136 0.00512 -0.1384" quat="0.777852 -0.0416277 -0.034227 0.626132" mass="1.721" | ||
- diaginertia="0.0125237 0.0123104 0.0019428"/> | ||
- <joint name="right_knee" axis="0 1 0" range="-0.26 2.05"/> | ||
- <geom class="visual" mesh="right_knee_link"/> | ||
- <geom class="collision" type="capsule" size="0.025" fromto="0.02 0 -0.4 0.02 0 0"/> | ||
- <geom class="collision" type="sphere" size="0.05" pos="0 0 -0.115"/> | ||
- <body name="right_ankle_link" pos="0 0 -0.4"> | ||
- <inertial pos="0.06722 -0.00015 -0.04497" quat="0.432972 0.565782 0.503197 0.489101" mass="0.446" | ||
- diaginertia="0.00220848 0.00218961 0.000214202"/> | ||
- <joint name="right_ankle" axis="0 1 0" range="-0.87 0.52"/> | ||
- <geom class="visual" mesh="right_ankle_link"/> | ||
- <geom class="foot1"/> | ||
- <geom class="foot2"/> | ||
- <geom class="foot3"/> | ||
- </body> | ||
+ <body name="right_hip_yaw_link" pos="0 -0.0875 -0.1742"> | ||
+ <inertial pos="-0.04923 -0.0001 0.0072" quat="0.641667 0.233287 0.219193 0.69699" mass="2.244" | ||
+ diaginertia="0.00304494 0.00296885 0.00189201"/> | ||
+ <joint name="right_hip_yaw" axis="0 0 1" range="-0.43 0.43"/> | ||
+ <geom class="visual" mesh="right_hip_yaw_link"/> | ||
+ <geom size="0.06 0.035" pos="-0.067 0 0" quat="0.707123 0 0.70709 0" type="cylinder" class="collision"/> | ||
+ <body name="right_hip_roll_link" pos="0.039468 0 0"> | ||
+ <inertial pos="-0.0058 0.00319 -9e-05" quat="-0.0438242 0.70721 0.0729075 0.701867" mass="2.232" | ||
+ diaginertia="0.00243264 0.00225325 0.00205492"/> | ||
+ <joint name="right_hip_roll" axis="1 0 0" range="-0.43 0.43"/> | ||
+ <geom class="visual" mesh="right_hip_roll_link"/> | ||
+ <geom class="collision" type="cylinder" size="0.05 0.03" quat="1 1 0 0" pos="0 0.02 0"/> | ||
+ <body name="right_hip_pitch_link" pos="0 -0.11536 0"> | ||
+ <inertial pos="0.00746 0.02346 -0.08193" quat="0.979828 -0.0513522 -0.0169854 0.192382" mass="4.152" | ||
+ diaginertia="0.0829503 0.0821457 0.00510909"/> | ||
+ <joint name="right_hip_pitch" axis="0 1 0" range="-1.57 1.57"/> | ||
+ <geom class="visual" mesh="right_hip_pitch_link"/> | ||
+ <geom class="collision" type="capsule" size="0.03" fromto="0.02 0 -0.4 -0.02 0 0.02"/> | ||
+ <geom class="collision" type="capsule" size="0.03" fromto="0.02 0 -0.4 0.02 0 0.02"/> | ||
+ <geom class="collision" type="cylinder" size="0.05 0.02" quat="1 1 0 0" pos="0 0.07 0"/> | ||
+ <body name="right_knee_link" pos="0 0 -0.4"> | ||
+ <inertial pos="-0.00136 0.00512 -0.1384" quat="0.777852 -0.0416277 -0.034227 0.626132" mass="1.721" | ||
+ diaginertia="0.0125237 0.0123104 0.0019428"/> | ||
+ <joint name="right_knee" axis="0 1 0" range="-0.26 2.05"/> | ||
+ <geom class="visual" mesh="right_knee_link"/> | ||
+ <geom class="collision" type="capsule" size="0.025" fromto="0.02 0 -0.4 0.02 0 0"/> | ||
+ <geom class="collision" type="sphere" size="0.05" pos="0 0 -0.115"/> | ||
+ <body name="right_ankle_link" pos="0 0 -0.4"> | ||
+ <inertial pos="0.06722 -0.00015 -0.04497" quat="0.432972 0.565782 0.503197 0.489101" mass="0.446" | ||
+ diaginertia="0.00220848 0.00218961 0.000214202"/> | ||
+ <joint name="right_ankle" axis="0 1 0" range="-0.87 0.52"/> | ||
+ <geom class="visual" mesh="right_ankle_link"/> | ||
+ <geom class="foot1"/> | ||
+ <geom class="foot2"/> | ||
+ <geom class="foot3"/> | ||
+ </body> | ||
+ </body> | ||
+ </body> | ||
</body> | ||
- </body> | ||
</body> | ||
</body> | ||
<body name="torso_link"> | ||
@@ -153,6 +155,7 @@ | ||
<geom name="torso" class="collision" type="box" size="0.07 0.1 0.22" pos="0 0 0.25"/> | ||
<geom name="hip" class="collision" type="capsule" size="0.05" fromto="0 -0.1 -0.05 0 0.1 -0.05"/> | ||
<site name="imu" pos="-0.04452 -0.01891 0.27756"/> | ||
+ <site name="upper_torso" pos="0 0 0.40"/><!--ADDED--> | ||
<body name="left_shoulder_pitch_link" pos="0.0055 0.15535 0.42999" quat="0.976296 0.216438 0 0"> | ||
<inertial pos="0.005045 0.053657 -0.015715" quat="0.814858 0.579236 -0.0201072 -0.00936488" mass="1.033" | ||
diaginertia="0.00129936 0.000987113 0.000858198"/> | ||
@@ -239,4 +242,4 @@ | ||
<motor class="h1" name="right_shoulder_yaw" joint="right_shoulder_yaw" ctrlrange="-18 18"/> | ||
<motor class="h1" name="right_elbow" joint="right_elbow" ctrlrange="-18 18"/> | ||
</actuator> | ||
-</mujoco> | ||
+</mujoco> | ||
\ No newline at end of file | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The xml file should have a new line at the end. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,79 @@ | ||
<mujoco model="H1 Locomotion"> | ||
<include file="../../common.xml"/> | ||
<include file="../h1_modified.xml" /> | ||
<size memory="400K"/> | ||
|
||
<visual> | ||
<global offwidth="1280" offheight="720"/> | ||
</visual> | ||
|
||
<worldbody> | ||
<light pos="0 0 3.5" dir="0 0 -1" directional="true"/> | ||
<geom name="floor" type="plane" conaffinity="1" size="50 50 .05" material="blue_grid"/> | ||
<camera name="top" mode="targetbody" target="pelvis" pos="10.0 1.0 3.5" /> | ||
<body name="goal" mocap="true" pos=".3 0 0.26"> | ||
<geom size="0.12" contype="0" conaffinity="0" rgba="0 1 0 .5" group="2"/> | ||
</body> | ||
</worldbody> | ||
|
||
<custom> | ||
<!-- agent --> | ||
<numeric name="agent_planner" data="2" /> | ||
<numeric name="agent_horizon" data="0.4" /> | ||
<numeric name="agent_timestep" data="0.02" /> | ||
<numeric name="agent_integrator" data="3" /> | ||
<numeric name="sampling_spline_points" data="3" /> | ||
<numeric name="sampling_exploration" data="0.05" /> | ||
<numeric name="gradient_spline_points" data="5" /> | ||
<numeric name="residual_Torso" data="1.30 1.0 1.7" /> | ||
<numeric name="residual_Speed" data="0.70 -3.0 3.0" /> | ||
<numeric name="residual_FeetDistance" data="0.4 0.0 1.0" /> | ||
<numeric name="residual_BalanceSpeed" data="0.3 0.0 1.0" /> | ||
</custom> | ||
|
||
<sensor> | ||
<!-- cost --> | ||
<user name="Height" dim="1" user="7 5.0 0 25.0 0.1 4.0" /> <!--kSmoothAbs2Loss --> | ||
<user name="Pelvis/Feet" dim="1" user="8 1.0 0.0 10.0 0.05" /> <!--kRectifyLoss--> | ||
<user name="Balance" dim="2" user="1 5.0 0.0 25.0 0.02 4.0" /> <!--kL22--> | ||
<user name="Upright" dim="8" user="2 4.0 0.0 25.0 0.01" /> <!--kL2--> | ||
<user name="Posture torso" dim="1" user="0 0.020 0 1.0" /> <!--kQuadratic--> | ||
<user name="Posture arms" dim="8" user="0 0.020 0 1.0" /> <!--kQuadratic--> | ||
<user name="Face goal" dim="4" user="7 2.0 0.0 25.0 0.5 3.0" /> <!--kSmoothAbs2Loss --> | ||
<user name="Walk forward" dim="1" user="7 7.88 0.0 25.0 0.5 3.0" /> <!--kSmoothAbs2Loss --> | ||
<user name="Move feet" dim="2" user="7 4.0 0 25.0 0.2 4.0" /> <!--kSmoothAbs2Loss --> | ||
<user name="Control" dim="19" user="0 0.00005 0.00001 0.001" /> <!--kQuadratic--> | ||
<user name="Feet Distance" dim="1" user="7 5.62 0 25.0 0.1 4.0" /> <!--kSmoothAbs2Loss--> | ||
<user name="Leg cross" dim="2" user="8 1.0 0.0 20.0 0.05" /> <!--kRectifyLoss--> | ||
<user name="Slippage" dim="2" user="0 0.0 0 50.0" /> <!--kQuadratic--> | ||
|
||
<!-- residual --> | ||
<framepos name="torso_position" objtype="body" objname="torso_link"/> | ||
<subtreecom name="torso_subcom" body="pelvis"/> <!--pelvis is the root node for the H1--> | ||
<subtreelinvel name="torso_subcomvel" body="pelvis"/> <!--pelvis is the root node for the H1--> | ||
<framepos name="foot_right" objtype="body" objname="right_ankle_link"/> | ||
<framepos name="foot_left" objtype="body" objname="left_ankle_link"/> | ||
<framepos name="foot_right_xbody" objtype="xbody" objname="right_ankle_link"/> | ||
<framepos name="foot_left_xbody" objtype="xbody" objname="left_ankle_link"/> | ||
<framepos name="pelvis_position" objtype="body" objname="pelvis"/> | ||
<framepos name="goal" objtype="xbody" objname="goal"/> | ||
<framezaxis name="torso_up" objtype="site" objname="upper_torso"/><!--upper_torso is between the shoulders--> | ||
<framezaxis name="pelvis_up" objtype="xbody" objname="pelvis"/> | ||
<framezaxis name="foot_right_up" objtype="xbody" objname="right_ankle_link"/> | ||
<framezaxis name="foot_left_up" objtype="xbody" objname="left_ankle_link"/> | ||
<frameyaxis name="foot_left_left" objtype="xbody" objname="left_ankle_link"/> | ||
<framexaxis name="torso_forward" objtype="site" objname="upper_torso"/> | ||
<framexaxis name="pelvis_forward" objtype="xbody" objname="pelvis"/> | ||
<framexaxis name="foot_right_forward" objtype="xbody" objname="right_ankle_link"/> | ||
<framexaxis name="foot_left_forward" objtype="xbody" objname="left_ankle_link"/> | ||
<framexaxis name="goal_forward" objtype="xbody" objname="goal"/> | ||
<subtreelinvel name="waist_lower_subcomvel" body="legs"/> | ||
<framelinvel name="torso_velocity" objtype="body" objname="torso_link"/> | ||
<framelinvel name="foot_right_velocity" objtype="body" objname="right_ankle_link"/> | ||
<framelinvel name="foot_left_velocity" objtype="body" objname="left_ankle_link"/> | ||
<frameangvel name="foot_right_ang_velocity" objtype="body" objname="right_ankle_link"/> | ||
<frameangvel name="foot_left_ang_velocity" objtype="body" objname="left_ankle_link"/> | ||
<jointpos name="right_hip_roll" joint="right_hip_roll"/> | ||
<jointpos name="left_hip_roll" joint="left_hip_roll"/> | ||
</sensor> | ||
</mujoco> |
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Please remove the file links to your machine. You can replace them with something generic like the other .patch files.