Update urdf paths
This commit is contained in:
parent
a6b48ce3f1
commit
cdd3cfb686
@ -1,6 +1,6 @@
|
|||||||
center: [0.5, 0.2, 0.25]
|
center: [0.5, 0.2, 0.25]
|
||||||
objects:
|
objects:
|
||||||
- object_id: 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}
|
||||||
|
@ -126,14 +126,11 @@ class YamlScene(Scene):
|
|||||||
self.length = 0.3
|
self.length = 0.3
|
||||||
self.origin = self.center - np.r_[0.5 * self.length, 0.5 * self.length, 0.0]
|
self.origin = self.center - np.r_[0.5 * self.length, 0.5 * self.length, 0.0]
|
||||||
|
|
||||||
def get_urdf_path(self, model_name):
|
|
||||||
return assets_dir / "ycb_subset" / model_name / "model.urdf"
|
|
||||||
|
|
||||||
def generate(self, rng):
|
def generate(self, rng):
|
||||||
self.load_config()
|
self.load_config()
|
||||||
self.add_support(self.center)
|
self.add_support(self.center)
|
||||||
for object in self.scene["objects"]:
|
for object in self.scene["objects"]:
|
||||||
urdf = self.get_urdf_path(object["object_id"])
|
urdf = assets_dir / object["object_id"] / "model.urdf"
|
||||||
ori = Rotation.from_euler("xyz", object["rpy"], degrees=True)
|
ori = Rotation.from_euler("xyz", object["rpy"], degrees=True)
|
||||||
pos = self.center + np.asarray(object["xyz"])
|
pos = self.center + np.asarray(object["xyz"])
|
||||||
scale = object.get("scale", 1)
|
scale = object.get("scale", 1)
|
||||||
|
Loading…
x
Reference in New Issue
Block a user