Fix PointEnv.set_state
This commit is contained in:
parent
f507209fd9
commit
025e774516
@ -22,7 +22,6 @@
|
|||||||
<joint name='bally' type='slide' axis='0 1 0' pos='0 0 0' />
|
<joint name='bally' type='slide' axis='0 1 0' pos='0 0 0' />
|
||||||
<joint name='rot' type='hinge' axis='0 0 1' pos='0 0 0' limited="false" />
|
<joint name='rot' type='hinge' axis='0 0 1' pos='0 0 0' limited="false" />
|
||||||
</body>
|
</body>
|
||||||
|
|
||||||
<!-- Goal / target position -->
|
<!-- Goal / target position -->
|
||||||
<geom name="target" type="sphere" size="0.5" pos="0 8 0" rgba="1. 0. 0. 0.6" />
|
<geom name="target" type="sphere" size="0.5" pos="0 8 0" rgba="1. 0. 0. 0.6" />
|
||||||
</worldbody>
|
</worldbody>
|
||||||
|
@ -99,3 +99,4 @@ class PointEnv(mujoco_env.MujocoEnv, utils.EzPickle):
|
|||||||
qpos[1] = xy[1]
|
qpos[1] = xy[1]
|
||||||
|
|
||||||
qvel = self.physics.data.qvel
|
qvel = self.physics.data.qvel
|
||||||
|
self.set_state(qpos, qvel)
|
||||||
|
Loading…
Reference in New Issue
Block a user