File tree Expand file tree Collapse file tree 3 files changed +7
-3
lines changed Expand file tree Collapse file tree 3 files changed +7
-3
lines changed Original file line number Diff line number Diff line change @@ -11,6 +11,7 @@ Built by the Google DeepMind team with contributions from the open-source commun
1111- [ Saran Tunyasuvunakool] ( https://github.com/saran-t ) — Google DeepMind
1212- [ Tom Erez] ( https://github.com/erez-tom ) — Google DeepMind
1313- [ Yuval Tassa] ( https://github.com/yuvaltassa ) — Google DeepMind
14+ - [ Silvia Cruciani] ( https://github.com/silviacruciani ) - Google DeepMind
1415
1516## Community Contributors
1617
Original file line number Diff line number Diff line change 22
33All notable changes to this model will be documented in this file.
44
5+ ## [ 2025-08-7]
6+ - Update the right hip joint limit of [ g1_mjx.xml] ( g1_mjx.xml ) to match the real robot limits
7+
58## [ 2025-05-30]
69
710- Add MJX variant of [ g1.xml] ( g1.xml ) , with manually designed collision geoms and contact pairs.
Original file line number Diff line number Diff line change 3030 <joint axis =" 0 1 0" range =" -2.5307 2.8798" actuatorfrcrange =" -88 88" armature =" 0.01017752004" />
3131 </default >
3232 <default class =" hip_roll" >
33- <joint axis =" 1 0 0" range = " -0.5236 2.9671 " actuatorfrcrange =" -139 139" armature =" 0.025101925" />
33+ <joint axis =" 1 0 0" actuatorfrcrange =" -139 139" armature =" 0.025101925" />
3434 </default >
3535 <default class =" hip_yaw" >
3636 <joint axis =" 0 0 1" range =" -2.7576 2.7576" actuatorfrcrange =" -88 88" armature =" 0.01017752004" />
149149 <body name =" left_hip_roll_link" pos =" 0 0.052 -0.030465" quat =" 0.996179 0 -0.0873386 0" >
150150 <inertial pos =" 0.029812 -0.001045 -0.087934" quat =" 0.977808 -1.97119e-05 0.205576 -0.0403793" mass =" 1.52"
151151 diaginertia =" 0.00254986 0.00241169 0.00148755" />
152- <joint name =" left_hip_roll_joint" class =" hip_roll" />
152+ <joint name =" left_hip_roll_joint" range = " -0.5236 2.9671 " class =" hip_roll" />
153153 <geom class =" visual" mesh =" left_hip_roll_link" />
154154 <geom name =" left_hip_collision" class =" collision" size =" 0.06" fromto =" 0.02 0 0 0.02 0 -0.08" />
155155 <body name =" left_hip_yaw_link" pos =" 0.025001 0 -0.12412" >
195195 <body name =" right_hip_roll_link" pos =" 0 -0.052 -0.030465" quat =" 0.996179 0 -0.0873386 0" >
196196 <inertial pos =" 0.029812 0.001045 -0.087934" quat =" 0.977808 1.97119e-05 0.205576 0.0403793" mass =" 1.52"
197197 diaginertia =" 0.00254986 0.00241169 0.00148755" />
198- <joint name =" right_hip_roll_joint" class =" hip_roll" />
198+ <joint name =" right_hip_roll_joint" range = " -2.9671 0.5236 " class =" hip_roll" />
199199 <geom class =" visual" mesh =" right_hip_roll_link" />
200200 <geom name =" right_hip_collision" class =" collision" size =" 0.06" fromto =" 0.02 0 0 0.02 0 -0.08" />
201201 <body name =" right_hip_yaw_link" pos =" 0.025001 0 -0.12412" >
You can’t perform that action at this time.
0 commit comments