Specify xyz bounds for randomizing object location
This commit is contained in:
parent
cdd3cfb686
commit
7db03ff39e
@ -3,5 +3,5 @@ objects:
|
|||||||
- object_id: ycb/006_mustard_bottle
|
- object_id: ycb/006_mustard_bottle
|
||||||
xyz: [0.0, 0.0, 0.0]
|
xyz: [0.0, 0.0, 0.0]
|
||||||
rpy: [0, 0, -50]
|
rpy: [0, 0, -50]
|
||||||
randomize: {rot: 5, pos: 0.02}
|
randomize: {rot: 5, pos: [0.02, 0.02, 0]}
|
||||||
q: [0.0, -1.39, 0.0, -2.36, 0.0, 1.57, 0.79]
|
q: [0.0, -1.39, 0.0, -2.36, 0.0, 1.57, 0.79]
|
||||||
|
@ -137,7 +137,8 @@ class YamlScene(Scene):
|
|||||||
if randomize := object.get("randomize", False):
|
if randomize := object.get("randomize", False):
|
||||||
angle = rng.uniform(-randomize["rot"], randomize["rot"])
|
angle = rng.uniform(-randomize["rot"], randomize["rot"])
|
||||||
ori *= Rotation.from_euler("z", angle, degrees=True)
|
ori *= Rotation.from_euler("z", angle, degrees=True)
|
||||||
pos[:2] += rng.uniform(-randomize["pos"], randomize["pos"], 2)
|
b = np.asarray(randomize["pos"])
|
||||||
|
pos += rng.uniform(-b, b)
|
||||||
self.add_object(urdf, ori, pos, scale)
|
self.add_object(urdf, ori, pos, scale)
|
||||||
for _ in range(60):
|
for _ in range(60):
|
||||||
p.stepSimulation()
|
p.stepSimulation()
|
||||||
|
Loading…
x
Reference in New Issue
Block a user