Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CONTRIBUTORS.md
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ Built by the Google DeepMind team with contributions from the open-source commun
- [Saran Tunyasuvunakool](https://github.com/saran-t) — Google DeepMind
- [Tom Erez](https://github.com/erez-tom) — Google DeepMind
- [Yuval Tassa](https://github.com/yuvaltassa) — Google DeepMind
- [Silvia Cruciani](https://github.com/silviacruciani) - Google DeepMind

## Community Contributors

Expand Down
3 changes: 3 additions & 0 deletions unitree_g1/CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@

All notable changes to this model will be documented in this file.

## [2025-08-7]
- Update the right hip joint limit of [g1_mjx.xml](g1_mjx.xml) to match the real robot limits

## [2025-05-30]

- Add MJX variant of [g1.xml](g1.xml), with manually designed collision geoms and contact pairs.
Expand Down
6 changes: 3 additions & 3 deletions unitree_g1/g1_mjx.xml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
<joint axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88" armature="0.01017752004"/>
</default>
<default class="hip_roll">
<joint axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-139 139" armature="0.025101925"/>
<joint axis="1 0 0" actuatorfrcrange="-139 139" armature="0.025101925"/>
</default>
<default class="hip_yaw">
<joint axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88" armature="0.01017752004"/>
Expand Down Expand Up @@ -149,7 +149,7 @@
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52"
diaginertia="0.00254986 0.00241169 0.00148755"/>
<joint name="left_hip_roll_joint" class="hip_roll"/>
<joint name="left_hip_roll_joint" range="-0.5236 2.9671" class="hip_roll"/>
<geom class="visual" mesh="left_hip_roll_link"/>
<geom name="left_hip_collision" class="collision" size="0.06" fromto="0.02 0 0 0.02 0 -0.08"/>
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
Expand Down Expand Up @@ -195,7 +195,7 @@
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52"
diaginertia="0.00254986 0.00241169 0.00148755"/>
<joint name="right_hip_roll_joint" class="hip_roll"/>
<joint name="right_hip_roll_joint" range="-2.9671 0.5236" class="hip_roll"/>
<geom class="visual" mesh="right_hip_roll_link"/>
<geom name="right_hip_collision" class="collision" size="0.06" fromto="0.02 0 0 0.02 0 -0.08"/>
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
Expand Down